slugs.xml 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313
  1. <?xml version="1.0"?>
  2. <mavlink>
  3. <include>common.xml</include>
  4. <enums>
  5. <enum name="MAV_CMD">
  6. <!-- 1-10000 reserved for common commands -->
  7. <entry value="10001" name="MAV_CMD_DO_NOTHING">
  8. <description>Does nothing.</description>
  9. <param index="1">1 to arm, 0 to disarm</param>
  10. </entry>
  11. <!-- Unused Commands -->
  12. <!--
  13. <entry value="10002" name="MAV_CMD_CALIBRATE_RC">
  14. <description>Initiate radio control calibration.</description>
  15. </entry>
  16. <entry value="10003" name="MAV_CMD_CALIBRATE_MAGNETOMETER">
  17. <description>Stops recording data.</description>
  18. </entry>
  19. <entry value="10004" name="MAV_CMD_START_RECORDING">
  20. <description>Start recording data.</description>
  21. </entry>
  22. <entry value="10005" name="MAV_CMD_PAUSE_RECORDING">
  23. <description>Pauses recording data.</description>
  24. </entry>
  25. <entry value="10006" name="MAV_CMD_STOP_RECORDING">
  26. <description>Stops recording data.</description>
  27. </entry>
  28. -->
  29. <!-- Old MAVlink Common Actions -->
  30. <entry value="10011" name="MAV_CMD_RETURN_TO_BASE">
  31. <description>Return vehicle to base.</description>
  32. <param index="1">0: return to base, 1: track mobile base</param>
  33. </entry>
  34. <entry value="10012" name="MAV_CMD_STOP_RETURN_TO_BASE">
  35. <description>Stops the vehicle from returning to base and resumes flight. </description>
  36. </entry>
  37. <entry value="10013" name="MAV_CMD_TURN_LIGHT">
  38. <description>Turns the vehicle's visible or infrared lights on or off.</description>
  39. <param index="1">0: visible lights, 1: infrared lights</param>
  40. <param index="2">0: turn on, 1: turn off</param>
  41. </entry>
  42. <entry value="10014" name="MAV_CMD_GET_MID_LEVEL_COMMANDS">
  43. <description>Requests vehicle to send current mid-level commands to ground station.</description>
  44. </entry>
  45. <entry value="10015" name="MAV_CMD_MIDLEVEL_STORAGE">
  46. <description>Requests storage of mid-level commands.</description>
  47. <param index="1">Mid-level command storage: 0: read from flash/EEPROM, 1: write to flash/EEPROM</param>
  48. </entry>
  49. <!-- From SLUGS_ACTION Enum -->
  50. </enum>
  51. <enum name="SLUGS_MODE">
  52. <description>Slugs-specific navigation modes.</description>
  53. <entry value="0" name="SLUGS_MODE_NONE">
  54. <description>No change to SLUGS mode.</description>
  55. </entry>
  56. <entry value="1" name="SLUGS_MODE_LIFTOFF">
  57. <description>Vehicle is in liftoff mode.</description>
  58. </entry>
  59. <entry value="2" name="SLUGS_MODE_PASSTHROUGH">
  60. <description>Vehicle is in passthrough mode, being controlled by a pilot.</description>
  61. </entry>
  62. <entry value="3" name="SLUGS_MODE_WAYPOINT">
  63. <description>Vehicle is in waypoint mode, navigating to waypoints.</description>
  64. </entry>
  65. <entry value="4" name="SLUGS_MODE_MID_LEVEL">
  66. <description>Vehicle is executing mid-level commands.</description>
  67. </entry>
  68. <entry value="5" name="SLUGS_MODE_RETURNING">
  69. <description>Vehicle is returning to the home location.</description>
  70. </entry>
  71. <entry value="6" name="SLUGS_MODE_LANDING">
  72. <description>Vehicle is landing.</description>
  73. </entry>
  74. <entry value="7" name="SLUGS_MODE_LOST">
  75. <description>Lost connection with vehicle.</description>
  76. </entry>
  77. <entry value="8" name="SLUGS_MODE_SELECTIVE_PASSTHROUGH">
  78. <description>Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled.</description>
  79. </entry>
  80. <entry value="9" name="SLUGS_MODE_ISR">
  81. <description>Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message.</description>
  82. </entry>
  83. <entry value="10" name="SLUGS_MODE_LINE_PATROL">
  84. <description>Vehicle is patrolling along lines between waypoints.</description>
  85. </entry>
  86. <entry value="11" name="SLUGS_MODE_GROUNDED">
  87. <description>Vehicle is grounded or an error has occurred.</description>
  88. </entry>
  89. </enum>
  90. <enum name="CONTROL_SURFACE_FLAG">
  91. <description>These flags encode the control surfaces for selective passthrough mode. If a bit is set then the pilot console
  92. has control of the surface, and if not then the autopilot has control of the surface.</description>
  93. <entry value="128" name="CONTROL_SURFACE_FLAG_THROTTLE">
  94. <description>0b10000000 Throttle control passes through to pilot console.</description>
  95. </entry>
  96. <entry value="64" name="CONTROL_SURFACE_FLAG_LEFT_AILERON">
  97. <description>0b01000000 Left aileron control passes through to pilot console.</description>
  98. </entry>
  99. <entry value="32" name="CONTROL_SURFACE_FLAG_RIGHT_AILERON">
  100. <description>0b00100000 Right aileron control passes through to pilot console.</description>
  101. </entry>
  102. <entry value="16" name="CONTROL_SURFACE_FLAG_RUDDER">
  103. <description>0b00010000 Rudder control passes through to pilot console.</description>
  104. </entry>
  105. <entry value="8" name="CONTROL_SURFACE_FLAG_LEFT_ELEVATOR">
  106. <description>0b00001000 Left elevator control passes through to pilot console.</description>
  107. </entry>
  108. <entry value="4" name="CONTROL_SURFACE_FLAG_RIGHT_ELEVATOR">
  109. <description>0b00000100 Right elevator control passes through to pilot console.</description>
  110. </entry>
  111. <entry value="2" name="CONTROL_SURFACE_FLAG_LEFT_FLAP">
  112. <description>0b00000010 Left flap control passes through to pilot console.</description>
  113. </entry>
  114. <entry value="1" name="CONTROL_SURFACE_FLAG_RIGHT_FLAP">
  115. <description>0b00000001 Right flap control passes through to pilot console.</description>
  116. </entry>
  117. </enum>
  118. </enums>
  119. <!--
  120. <enum name="WP_PROTOCOL_STATE" >
  121. <description> Waypoint Protocol States </description>
  122. <entry name = "WP_PROT_IDLE">
  123. <entry name = "WP_PROT_LIST_REQUESTED">
  124. <entry name = "WP_PROT_NUM_SENT">
  125. <entry name = "WP_PROT_TX_WP">
  126. <entry name = "WP_PROT_RX_WP">
  127. <entry name = "WP_PROT_SENDING_WP_IDLE">
  128. <entry name = "WP_PROT_GETTING_WP_IDLE">
  129. </enum>
  130. -->
  131. <messages>
  132. <message name="CPU_LOAD" id="170">
  133. <description>Sensor and DSC control loads.</description>
  134. <field name="sensLoad" type="uint8_t">Sensor DSC Load</field>
  135. <field name="ctrlLoad" type="uint8_t">Control DSC Load</field>
  136. <field name="batVolt" type="uint16_t" units="mV">Battery Voltage</field>
  137. </message>
  138. <message name="SENSOR_BIAS" id="172">
  139. <description>Accelerometer and gyro biases.</description>
  140. <field name="axBias" type="float" units="m/s">Accelerometer X bias</field>
  141. <field name="ayBias" type="float" units="m/s">Accelerometer Y bias</field>
  142. <field name="azBias" type="float" units="m/s">Accelerometer Z bias</field>
  143. <field name="gxBias" type="float" units="rad/s">Gyro X bias</field>
  144. <field name="gyBias" type="float" units="rad/s">Gyro Y bias</field>
  145. <field name="gzBias" type="float" units="rad/s">Gyro Z bias</field>
  146. </message>
  147. <message name="DIAGNOSTIC" id="173">
  148. <description>Configurable diagnostic messages.</description>
  149. <field name="diagFl1" type="float">Diagnostic float 1</field>
  150. <field name="diagFl2" type="float">Diagnostic float 2</field>
  151. <field name="diagFl3" type="float">Diagnostic float 3</field>
  152. <field name="diagSh1" type="int16_t">Diagnostic short 1</field>
  153. <field name="diagSh2" type="int16_t">Diagnostic short 2</field>
  154. <field name="diagSh3" type="int16_t">Diagnostic short 3</field>
  155. </message>
  156. <message name="SLUGS_NAVIGATION" id="176">
  157. <description>Data used in the navigation algorithm.</description>
  158. <field name="u_m" type="float" units="m/s">Measured Airspeed prior to the nav filter</field>
  159. <field name="phi_c" type="float">Commanded Roll</field>
  160. <field name="theta_c" type="float">Commanded Pitch</field>
  161. <field name="psiDot_c" type="float">Commanded Turn rate</field>
  162. <field name="ay_body" type="float">Y component of the body acceleration</field>
  163. <field name="totalDist" type="float">Total Distance to Run on this leg of Navigation</field>
  164. <field name="dist2Go" type="float">Remaining distance to Run on this leg of Navigation</field>
  165. <field name="fromWP" type="uint8_t">Origin WP</field>
  166. <field name="toWP" type="uint8_t">Destination WP</field>
  167. <field name="h_c" type="uint16_t" units="dm">Commanded altitude (MSL)</field>
  168. </message>
  169. <message name="DATA_LOG" id="177">
  170. <description>Configurable data log probes to be used inside Simulink</description>
  171. <field name="fl_1" type="float">Log value 1 </field>
  172. <field name="fl_2" type="float">Log value 2 </field>
  173. <field name="fl_3" type="float">Log value 3 </field>
  174. <field name="fl_4" type="float">Log value 4 </field>
  175. <field name="fl_5" type="float">Log value 5 </field>
  176. <field name="fl_6" type="float">Log value 6 </field>
  177. </message>
  178. <message name="GPS_DATE_TIME" id="179">
  179. <description>Pilot console PWM messges.</description>
  180. <field name="year" type="uint8_t">Year reported by Gps </field>
  181. <field name="month" type="uint8_t">Month reported by Gps </field>
  182. <field name="day" type="uint8_t">Day reported by Gps </field>
  183. <field name="hour" type="uint8_t">Hour reported by Gps </field>
  184. <field name="min" type="uint8_t">Min reported by Gps </field>
  185. <field name="sec" type="uint8_t">Sec reported by Gps </field>
  186. <field name="clockStat" type="uint8_t">Clock Status. See table 47 page 211 OEMStar Manual </field>
  187. <field name="visSat" type="uint8_t">Visible satellites reported by Gps </field>
  188. <field name="useSat" type="uint8_t">Used satellites in Solution </field>
  189. <field name="GppGl" type="uint8_t">GPS+GLONASS satellites in Solution </field>
  190. <field name="sigUsedMask" type="uint8_t">GPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?)</field>
  191. <field name="percentUsed" type="uint8_t" units="%">Percent used GPS</field>
  192. </message>
  193. <message name="MID_LVL_CMDS" id="180">
  194. <description>Mid Level commands sent from the GS to the autopilot. These are only sent when being operated in mid-level commands mode from the ground.</description>
  195. <field name="target" type="uint8_t">The system setting the commands</field>
  196. <field name="hCommand" type="float" units="m">Commanded altitude (MSL)</field>
  197. <field name="uCommand" type="float" units="m/s">Commanded Airspeed</field>
  198. <field name="rCommand" type="float" units="rad/s">Commanded Turnrate</field>
  199. </message>
  200. <message name="CTRL_SRFC_PT" id="181">
  201. <description>This message sets the control surfaces for selective passthrough mode.</description>
  202. <field name="target" type="uint8_t">The system setting the commands</field>
  203. <field name="bitfieldPt" type="uint16_t" enum="CONTROL_SURFACE_FLAG" display="bitmask">Bitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM.</field>
  204. </message>
  205. <message name="SLUGS_CAMERA_ORDER" id="184">
  206. <description>Orders generated to the SLUGS camera mount. </description>
  207. <field name="target" type="uint8_t">The system reporting the action</field>
  208. <field name="pan" type="int8_t">Order the mount to pan: -1 left, 0 No pan motion, +1 right</field>
  209. <field name="tilt" type="int8_t">Order the mount to tilt: -1 down, 0 No tilt motion, +1 up</field>
  210. <field name="zoom" type="int8_t">Order the zoom values 0 to 10</field>
  211. <field name="moveHome" type="int8_t">Orders the camera mount to move home. The other fields are ignored when this field is set. 1: move home, 0 ignored</field>
  212. </message>
  213. <message name="CONTROL_SURFACE" id="185">
  214. <description>Control for surface; pending and order to origin.</description>
  215. <field name="target" type="uint8_t">The system setting the commands</field>
  216. <field name="idSurface" type="uint8_t">ID control surface send 0: throttle 1: aileron 2: elevator 3: rudder</field>
  217. <field name="mControl" type="float">Pending</field>
  218. <field name="bControl" type="float">Order to origin</field>
  219. </message>
  220. <!-- Moved into MAV_CMD_RETURN_TO_BASE -->
  221. <!--
  222. <message name="SLUGS_RTB" id="187">
  223. <description>Orders SLUGS to RTB. It also decides to either track a mobile or RTB </description>
  224. <field name="target" type="uint8_t">The system ordered to RTB</field>
  225. <field name="rtb" type="uint8_t">Order SLUGS to: 0: Stop RTB and resume flight; 1: RTB</field>
  226. <field name="track_mobile" type="uint8_t">Order SLUGS to: 0: RTB to GS Location; 1: Track mobile </field>
  227. </message>
  228. -->
  229. <message name="SLUGS_MOBILE_LOCATION" id="186">
  230. <description>Transmits the last known position of the mobile GS to the UAV. Very relevant when Track Mobile is enabled</description>
  231. <field name="target" type="uint8_t">The system reporting the action</field>
  232. <field name="latitude" type="float" units="deg">Mobile Latitude</field>
  233. <field name="longitude" type="float" units="deg">Mobile Longitude</field>
  234. </message>
  235. <message name="SLUGS_CONFIGURATION_CAMERA" id="188">
  236. <description>Control for camara.</description>
  237. <field name="target" type="uint8_t">The system setting the commands</field>
  238. <field name="idOrder" type="uint8_t">ID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight</field>
  239. <field name="order" type="uint8_t"> 1: up/on 2: down/off 3: auto/reset/no action</field>
  240. </message>
  241. <message name="ISR_LOCATION" id="189">
  242. <description>Transmits the position of watch</description>
  243. <field name="target" type="uint8_t">The system reporting the action</field>
  244. <field name="latitude" type="float" units="deg">ISR Latitude</field>
  245. <field name="longitude" type="float" units="deg">ISR Longitude</field>
  246. <field name="height" type="float">ISR Height</field>
  247. <field name="option1" type="uint8_t">Option 1</field>
  248. <field name="option2" type="uint8_t">Option 2</field>
  249. <field name="option3" type="uint8_t">Option 3</field>
  250. </message>
  251. <!-- Removed to MAV_CMD_TURN_LIGHT -->
  252. <!--
  253. <message name="TURN_LIGHT" id="190">
  254. <description>Transmits the order to turn on lights</description>
  255. <field name="target" type="uint8_t">The system ordered to turn on lights</field>
  256. <field name="type" type="uint8_t">Type lights 0: Visible; 1: Infrared</field>
  257. <field name="turn" type="uint8_t">Order turn on lights 1: Turn on; 0: Turn off</field>
  258. </message>
  259. -->
  260. <message name="VOLT_SENSOR" id="191">
  261. <description>Transmits the readings from the voltage and current sensors</description>
  262. <field name="r2Type" type="uint8_t">It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM</field>
  263. <field name="voltage" type="uint16_t">Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V </field>
  264. <field name="reading2" type="uint16_t">Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value</field>
  265. </message>
  266. <message name="PTZ_STATUS" id="192">
  267. <description>Transmits the actual Pan, Tilt and Zoom values of the camera unit</description>
  268. <field name="zoom" type="uint8_t">The actual Zoom Value</field>
  269. <field name="pan" type="int16_t">The Pan value in 10ths of degree</field>
  270. <field name="tilt" type="int16_t">The Tilt value in 10ths of degree</field>
  271. </message>
  272. <message name="UAV_STATUS" id="193">
  273. <description>Transmits the actual status values UAV in flight</description>
  274. <field name="target" type="uint8_t">The ID system reporting the action</field>
  275. <field name="latitude" type="float" units="deg">Latitude UAV</field>
  276. <field name="longitude" type="float" units="deg">Longitude UAV</field>
  277. <field name="altitude" type="float" units="m">Altitude UAV</field>
  278. <field name="speed" type="float" units="m/s">Speed UAV</field>
  279. <field name="course" type="float">Course UAV</field>
  280. </message>
  281. <message name="STATUS_GPS" id="194">
  282. <description>This contains the status of the GPS readings</description>
  283. <field name="csFails" type="uint16_t">Number of times checksum has failed</field>
  284. <field name="gpsQuality" type="uint8_t">The quality indicator, 0=fix not available or invalid, 1=GPS fix, 2=C/A differential GPS, 6=Dead reckoning mode, 7=Manual input mode (fixed position), 8=Simulator mode, 9= WAAS a</field>
  285. <field name="msgsType" type="uint8_t"> Indicates if GN, GL or GP messages are being received</field>
  286. <field name="posStatus" type="uint8_t"> A = data valid, V = data invalid</field>
  287. <field name="magVar" type="float" units="deg">Magnetic variation</field>
  288. <field name="magDir" type="int8_t"> Magnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course</field>
  289. <field name="modeInd" type="uint8_t"> Positioning system mode indicator. A - Autonomous;D-Differential; E-Estimated (dead reckoning) mode;M-Manual input; N-Data not valid</field>
  290. </message>
  291. <message name="NOVATEL_DIAG" id="195">
  292. <description>Transmits the diagnostics data from the Novatel OEMStar GPS</description>
  293. <field name="timeStatus" type="uint8_t">The Time Status. See Table 8 page 27 Novatel OEMStar Manual</field>
  294. <field name="receiverStatus" type="uint32_t">Status Bitfield. See table 69 page 350 Novatel OEMstar Manual</field>
  295. <field name="solStatus" type="uint8_t">solution Status. See table 44 page 197</field>
  296. <field name="posType" type="uint8_t">position type. See table 43 page 196</field>
  297. <field name="velType" type="uint8_t">velocity type. See table 43 page 196</field>
  298. <field name="posSolAge" type="float" units="s">Age of the position solution</field>
  299. <field name="csFails" type="uint16_t">Times the CRC has failed since boot</field>
  300. </message>
  301. <message name="SENSOR_DIAG" id="196">
  302. <description>Diagnostic data Sensor MCU</description>
  303. <field name="float1" type="float">Float field 1</field>
  304. <field name="float2" type="float">Float field 2</field>
  305. <field name="int1" type="int16_t">Int 16 field 1</field>
  306. <field name="char1" type="int8_t">Int 8 field 1</field>
  307. </message>
  308. <message id="197" name="BOOT">
  309. <description>The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. This message allows the sensor and control MCUs to communicate version numbers on startup.</description>
  310. <field type="uint32_t" name="version">The onboard software version</field>
  311. </message>
  312. </messages>
  313. </mavlink>