ASLUAV.xml 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285
  1. <?xml version="1.0"?>
  2. <!-- ASLUAV Mavlink Message Definition File -->
  3. <!-- Used for the ASLUAV fixed-wing autopilot (www.asl.ethz.ch), which implements extensions to the Pixhawk (https://docs.px4.io/en/flight_controller/pixhawk.html) autopilot -->
  4. <mavlink>
  5. <include>common.xml</include>
  6. <enums>
  7. <enum name="MAV_CMD">
  8. <!-- ASLUAV specific MAV_CMD_* commands -->
  9. <entry name="MAV_CMD_RESET_MPPT" value="40001">
  10. <description>Mission command to reset Maximum Power Point Tracker (MPPT)</description>
  11. <param index="1">MPPT number</param>
  12. <param index="2">Empty</param>
  13. <param index="3">Empty</param>
  14. <param index="4">Empty</param>
  15. <param index="5">Empty</param>
  16. <param index="6">Empty</param>
  17. <param index="7">Empty</param>
  18. </entry>
  19. <entry name="MAV_CMD_PAYLOAD_CONTROL" value="40002">
  20. <description>Mission command to perform a power cycle on payload</description>
  21. <param index="1">Complete power cycle</param>
  22. <param index="2">VISensor power cycle</param>
  23. <param index="3">Empty</param>
  24. <param index="4">Empty</param>
  25. <param index="5">Empty</param>
  26. <param index="6">Empty</param>
  27. <param index="7">Empty</param>
  28. </entry>
  29. </enum>
  30. <enum name="GSM_LINK_TYPE">
  31. <entry value="0" name="GSM_LINK_TYPE_NONE">
  32. <description>no service</description>
  33. </entry>
  34. <entry value="1" name="GSM_LINK_TYPE_UNKNOWN">
  35. <description>link type unknown</description>
  36. </entry>
  37. <entry value="2" name="GSM_LINK_TYPE_2G">
  38. <description>2G (GSM/GRPS/EDGE) link</description>
  39. </entry>
  40. <entry value="3" name="GSM_LINK_TYPE_3G">
  41. <description>3G link (WCDMA/HSDPA/HSPA) </description>
  42. </entry>
  43. <entry value="4" name="GSM_LINK_TYPE_4G">
  44. <description>4G link (LTE)</description>
  45. </entry>
  46. </enum>
  47. <enum name="GSM_MODEM_TYPE">
  48. <entry value="0" name="GSM_MODEM_TYPE_UNKNOWN">
  49. <description>not specified</description>
  50. </entry>
  51. <entry name="GSM_MODEM_TYPE_HUAWEI_E3372">
  52. <description>HUAWEI LTE USB Stick E3372</description>
  53. </entry>
  54. </enum>
  55. </enums>
  56. <messages>
  57. <message id="78" name="COMMAND_INT_STAMPED">
  58. <description>Message encoding a command with parameters as scaled integers and additional metadata. Scaling depends on the actual command value.</description>
  59. <field type="uint32_t" name="utc_time">UTC time, seconds elapsed since 01.01.1970</field>
  60. <field type="uint64_t" name="vehicle_timestamp">Microseconds elapsed since vehicle boot</field>
  61. <field type="uint8_t" name="target_system">System ID</field>
  62. <field type="uint8_t" name="target_component">Component ID</field>
  63. <field type="uint8_t" name="frame" enum="MAV_FRAME">The coordinate system of the COMMAND, as defined by MAV_FRAME enum</field>
  64. <field type="uint16_t" name="command" enum="MAV_CMD">The scheduled action for the mission item, as defined by MAV_CMD enum</field>
  65. <field type="uint8_t" name="current">false:0, true:1</field>
  66. <field type="uint8_t" name="autocontinue">autocontinue to next wp</field>
  67. <field type="float" name="param1">PARAM1, see MAV_CMD enum</field>
  68. <field type="float" name="param2">PARAM2, see MAV_CMD enum</field>
  69. <field type="float" name="param3">PARAM3, see MAV_CMD enum</field>
  70. <field type="float" name="param4">PARAM4, see MAV_CMD enum</field>
  71. <field type="int32_t" name="x">PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7</field>
  72. <field type="int32_t" name="y">PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7</field>
  73. <field type="float" name="z">PARAM7 / z position: global: altitude in meters (MSL, WGS84, AGL or relative to home - depending on frame).</field>
  74. </message>
  75. <message id="79" name="COMMAND_LONG_STAMPED">
  76. <description>Send a command with up to seven parameters to the MAV and additional metadata</description>
  77. <field type="uint32_t" name="utc_time">UTC time, seconds elapsed since 01.01.1970</field>
  78. <field type="uint64_t" name="vehicle_timestamp">Microseconds elapsed since vehicle boot</field>
  79. <field type="uint8_t" name="target_system">System which should execute the command</field>
  80. <field type="uint8_t" name="target_component">Component which should execute the command, 0 for all components</field>
  81. <field type="uint16_t" name="command" enum="MAV_CMD">Command ID, as defined by MAV_CMD enum.</field>
  82. <field type="uint8_t" name="confirmation">0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)</field>
  83. <field type="float" name="param1">Parameter 1, as defined by MAV_CMD enum.</field>
  84. <field type="float" name="param2">Parameter 2, as defined by MAV_CMD enum.</field>
  85. <field type="float" name="param3">Parameter 3, as defined by MAV_CMD enum.</field>
  86. <field type="float" name="param4">Parameter 4, as defined by MAV_CMD enum.</field>
  87. <field type="float" name="param5">Parameter 5, as defined by MAV_CMD enum.</field>
  88. <field type="float" name="param6">Parameter 6, as defined by MAV_CMD enum.</field>
  89. <field type="float" name="param7">Parameter 7, as defined by MAV_CMD enum.</field>
  90. </message>
  91. <message id="201" name="SENS_POWER">
  92. <description>Voltage and current sensor data</description>
  93. <field type="float" name="adc121_vspb_volt" units="V"> Power board voltage sensor reading</field>
  94. <field type="float" name="adc121_cspb_amp" units="A"> Power board current sensor reading</field>
  95. <field type="float" name="adc121_cs1_amp" units="A"> Board current sensor 1 reading</field>
  96. <field type="float" name="adc121_cs2_amp" units="A"> Board current sensor 2 reading</field>
  97. </message>
  98. <message id="202" name="SENS_MPPT">
  99. <description>Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking</description>
  100. <field type="uint64_t" name="mppt_timestamp" units="us"> MPPT last timestamp </field>
  101. <field type="float" name="mppt1_volt" units="V"> MPPT1 voltage </field>
  102. <field type="float" name="mppt1_amp" units="A"> MPPT1 current </field>
  103. <field type="uint16_t" name="mppt1_pwm" units="us"> MPPT1 pwm </field>
  104. <field type="uint8_t" name="mppt1_status"> MPPT1 status </field>
  105. <field type="float" name="mppt2_volt" units="V"> MPPT2 voltage </field>
  106. <field type="float" name="mppt2_amp" units="A"> MPPT2 current </field>
  107. <field type="uint16_t" name="mppt2_pwm" units="us"> MPPT2 pwm </field>
  108. <field type="uint8_t" name="mppt2_status"> MPPT2 status </field>
  109. <field type="float" name="mppt3_volt" units="V">MPPT3 voltage </field>
  110. <field type="float" name="mppt3_amp" units="A"> MPPT3 current </field>
  111. <field type="uint16_t" name="mppt3_pwm" units="us"> MPPT3 pwm </field>
  112. <field type="uint8_t" name="mppt3_status"> MPPT3 status </field>
  113. </message>
  114. <message id="203" name="ASLCTRL_DATA">
  115. <description>ASL-fixed-wing controller data</description>
  116. <field type="uint64_t" name="timestamp" units="us"> Timestamp</field>
  117. <field type="uint8_t" name="aslctrl_mode"> ASLCTRL control-mode (manual, stabilized, auto, etc...)</field>
  118. <field type="float" name="h"> See sourcecode for a description of these values... </field>
  119. <field type="float" name="hRef"> </field>
  120. <field type="float" name="hRef_t"> </field>
  121. <field type="float" name="PitchAngle" units="deg">Pitch angle</field>
  122. <field type="float" name="PitchAngleRef" units="deg">Pitch angle reference</field>
  123. <field type="float" name="q"> </field>
  124. <field type="float" name="qRef"> </field>
  125. <field type="float" name="uElev"> </field>
  126. <field type="float" name="uThrot"> </field>
  127. <field type="float" name="uThrot2"> </field>
  128. <field type="float" name="nZ"> </field>
  129. <field type="float" name="AirspeedRef" units="m/s">Airspeed reference</field>
  130. <field type="uint8_t" name="SpoilersEngaged"> </field>
  131. <field type="float" name="YawAngle" units="deg">Yaw angle</field>
  132. <field type="float" name="YawAngleRef" units="deg">Yaw angle reference</field>
  133. <field type="float" name="RollAngle" units="deg">Roll angle</field>
  134. <field type="float" name="RollAngleRef" units="deg">Roll angle reference</field>
  135. <field type="float" name="p"> </field>
  136. <field type="float" name="pRef"> </field>
  137. <field type="float" name="r"> </field>
  138. <field type="float" name="rRef"> </field>
  139. <field type="float" name="uAil"> </field>
  140. <field type="float" name="uRud"> </field>
  141. </message>
  142. <message id="204" name="ASLCTRL_DEBUG">
  143. <description>ASL-fixed-wing controller debug data</description>
  144. <field type="uint32_t" name="i32_1"> Debug data</field>
  145. <field type="uint8_t" name="i8_1"> Debug data</field>
  146. <field type="uint8_t" name="i8_2"> Debug data</field>
  147. <field type="float" name="f_1"> Debug data </field>
  148. <field type="float" name="f_2"> Debug data</field>
  149. <field type="float" name="f_3"> Debug data</field>
  150. <field type="float" name="f_4"> Debug data</field>
  151. <field type="float" name="f_5"> Debug data</field>
  152. <field type="float" name="f_6"> Debug data</field>
  153. <field type="float" name="f_7"> Debug data</field>
  154. <field type="float" name="f_8"> Debug data</field>
  155. </message>
  156. <message id="205" name="ASLUAV_STATUS">
  157. <description>Extended state information for ASLUAVs</description>
  158. <field type="uint8_t" name="LED_status"> Status of the position-indicator LEDs</field>
  159. <field type="uint8_t" name="SATCOM_status"> Status of the IRIDIUM satellite communication system</field>
  160. <field type="uint8_t[8]" name="Servo_status"> Status vector for up to 8 servos</field>
  161. <field type="float" name="Motor_rpm"> Motor RPM </field>
  162. <!-- to be extended-->
  163. </message>
  164. <message id="206" name="EKF_EXT">
  165. <description>Extended EKF state estimates for ASLUAVs</description>
  166. <field type="uint64_t" name="timestamp" units="us"> Time since system start</field>
  167. <field type="float" name="Windspeed" units="m/s"> Magnitude of wind velocity (in lateral inertial plane)</field>
  168. <field type="float" name="WindDir" units="rad"> Wind heading angle from North</field>
  169. <field type="float" name="WindZ" units="m/s"> Z (Down) component of inertial wind velocity</field>
  170. <field type="float" name="Airspeed" units="m/s"> Magnitude of air velocity</field>
  171. <field type="float" name="beta" units="rad"> Sideslip angle</field>
  172. <field type="float" name="alpha" units="rad"> Angle of attack</field>
  173. </message>
  174. <message id="207" name="ASL_OBCTRL">
  175. <description>Off-board controls/commands for ASLUAVs</description>
  176. <field type="uint64_t" name="timestamp" units="us"> Time since system start</field>
  177. <field type="float" name="uElev"> Elevator command [~]</field>
  178. <field type="float" name="uThrot"> Throttle command [~]</field>
  179. <field type="float" name="uThrot2"> Throttle 2 command [~]</field>
  180. <field type="float" name="uAilL"> Left aileron command [~]</field>
  181. <field type="float" name="uAilR"> Right aileron command [~]</field>
  182. <field type="float" name="uRud"> Rudder command [~]</field>
  183. <field type="uint8_t" name="obctrl_status"> Off-board computer status</field>
  184. </message>
  185. <message id="208" name="SENS_ATMOS">
  186. <description>Atmospheric sensors (temperature, humidity, ...) </description>
  187. <field type="uint64_t" name="timestamp" units="us">Time since system boot</field>
  188. <field type="float" name="TempAmbient" units="degC"> Ambient temperature</field>
  189. <field type="float" name="Humidity" units="%"> Relative humidity</field>
  190. </message>
  191. <message id="209" name="SENS_BATMON">
  192. <description>Battery pack monitoring data for Li-Ion batteries</description>
  193. <field type="uint64_t" name="batmon_timestamp" units="us">Time since system start</field>
  194. <field type="float" name="temperature" units="degC">Battery pack temperature</field>
  195. <field type="uint16_t" name="voltage" units="mV">Battery pack voltage</field>
  196. <field type="int16_t" name="current" units="mA">Battery pack current</field>
  197. <field type="uint8_t" name="SoC">Battery pack state-of-charge</field>
  198. <field type="uint16_t" name="batterystatus">Battery monitor status report bits in Hex</field>
  199. <field type="uint16_t" name="serialnumber">Battery monitor serial number in Hex</field>
  200. <field type="uint32_t" name="safetystatus">Battery monitor safetystatus report bits in Hex</field>
  201. <field type="uint32_t" name="operationstatus">Battery monitor operation status report bits in Hex</field>
  202. <field type="uint16_t" name="cellvoltage1" units="mV">Battery pack cell 1 voltage</field>
  203. <field type="uint16_t" name="cellvoltage2" units="mV">Battery pack cell 2 voltage</field>
  204. <field type="uint16_t" name="cellvoltage3" units="mV">Battery pack cell 3 voltage</field>
  205. <field type="uint16_t" name="cellvoltage4" units="mV">Battery pack cell 4 voltage</field>
  206. <field type="uint16_t" name="cellvoltage5" units="mV">Battery pack cell 5 voltage</field>
  207. <field type="uint16_t" name="cellvoltage6" units="mV">Battery pack cell 6 voltage</field>
  208. </message>
  209. <message id="210" name="FW_SOARING_DATA">
  210. <description>Fixed-wing soaring (i.e. thermal seeking) data</description>
  211. <field type="uint64_t" name="timestamp" units="ms">Timestamp</field>
  212. <field type="uint64_t" name="timestampModeChanged" units="ms">Timestamp since last mode change</field>
  213. <field type="float" name="xW" units="m/s">Thermal core updraft strength</field>
  214. <field type="float" name="xR" units="m">Thermal radius</field>
  215. <field type="float" name="xLat" units="deg">Thermal center latitude</field>
  216. <field type="float" name="xLon" units="deg">Thermal center longitude</field>
  217. <field type="float" name="VarW">Variance W</field>
  218. <field type="float" name="VarR">Variance R</field>
  219. <field type="float" name="VarLat">Variance Lat</field>
  220. <field type="float" name="VarLon">Variance Lon </field>
  221. <field type="float" name="LoiterRadius" units="m">Suggested loiter radius</field>
  222. <field type="float" name="LoiterDirection">Suggested loiter direction</field>
  223. <field type="float" name="DistToSoarPoint" units="m">Distance to soar point</field>
  224. <field type="float" name="vSinkExp" units="m/s">Expected sink rate at current airspeed, roll and throttle</field>
  225. <field type="float" name="z1_LocalUpdraftSpeed" units="m/s">Measurement / updraft speed at current/local airplane position</field>
  226. <field type="float" name="z2_DeltaRoll" units="deg">Measurement / roll angle tracking error</field>
  227. <field type="float" name="z1_exp">Expected measurement 1</field>
  228. <field type="float" name="z2_exp">Expected measurement 2</field>
  229. <field type="float" name="ThermalGSNorth" units="m/s">Thermal drift (from estimator prediction step only)</field>
  230. <field type="float" name="ThermalGSEast" units="m/s">Thermal drift (from estimator prediction step only)</field>
  231. <field type="float" name="TSE_dot" units="m/s"> Total specific energy change (filtered)</field>
  232. <field type="float" name="DebugVar1"> Debug variable 1</field>
  233. <field type="float" name="DebugVar2"> Debug variable 2</field>
  234. <field type="uint8_t" name="ControlMode">Control Mode [-]</field>
  235. <field type="uint8_t" name="valid">Data valid [-]</field>
  236. </message>
  237. <message id="211" name="SENSORPOD_STATUS">
  238. <description>Monitoring of sensorpod status</description>
  239. <field type="uint64_t" name="timestamp" units="ms">Timestamp in linuxtime (since 1.1.1970)</field>
  240. <field type="uint8_t" name="visensor_rate_1">Rate of ROS topic 1</field>
  241. <field type="uint8_t" name="visensor_rate_2">Rate of ROS topic 2</field>
  242. <field type="uint8_t" name="visensor_rate_3">Rate of ROS topic 3</field>
  243. <field type="uint8_t" name="visensor_rate_4">Rate of ROS topic 4</field>
  244. <field type="uint8_t" name="recording_nodes_count">Number of recording nodes</field>
  245. <field type="uint8_t" name="cpu_temp" units="degC">Temperature of sensorpod CPU in</field>
  246. <field type="uint16_t" name="free_space">Free space available in recordings directory in [Gb] * 1e2</field>
  247. </message>
  248. <message id="212" name="SENS_POWER_BOARD">
  249. <description>Monitoring of power board status</description>
  250. <field type="uint64_t" name="timestamp" units="us">Timestamp</field>
  251. <field type="uint8_t" name="pwr_brd_status">Power board status register</field>
  252. <field type="uint8_t" name="pwr_brd_led_status">Power board leds status</field>
  253. <field type="float" name="pwr_brd_system_volt" units="V">Power board system voltage</field>
  254. <field type="float" name="pwr_brd_servo_volt" units="V">Power board servo voltage</field>
  255. <field type="float" name="pwr_brd_digital_volt" units="V">Power board digital voltage</field>
  256. <field type="float" name="pwr_brd_mot_l_amp" units="A">Power board left motor current sensor</field>
  257. <field type="float" name="pwr_brd_mot_r_amp" units="A">Power board right motor current sensor</field>
  258. <field type="float" name="pwr_brd_analog_amp" units="A">Power board analog current sensor</field>
  259. <field type="float" name="pwr_brd_digital_amp" units="A">Power board digital current sensor</field>
  260. <field type="float" name="pwr_brd_ext_amp" units="A">Power board extension current sensor</field>
  261. <field type="float" name="pwr_brd_aux_amp" units="A">Power board aux current sensor</field>
  262. </message>
  263. <message id="213" name="GSM_LINK_STATUS">
  264. <description>Status of GSM modem (connected to onboard computer)</description>
  265. <field type="uint64_t" name="timestamp" units="us">Timestamp (of OBC)</field>
  266. <field type="uint8_t" name="gsm_modem_type" enum="GSM_MODEM_TYPE">GSM modem used</field>
  267. <field type="uint8_t" name="gsm_link_type" enum="GSM_LINK_TYPE">GSM link type</field>
  268. <field type="uint8_t" name="rssi">RSSI as reported by modem (unconverted)</field>
  269. <field type="uint8_t" name="rsrp_rscp">RSRP (LTE) or RSCP (WCDMA) as reported by modem (unconverted)</field>
  270. <field type="uint8_t" name="sinr_ecio">SINR (LTE) or ECIO (WCDMA) as reported by modem (unconverted)</field>
  271. <field type="uint8_t" name="rsrq">RSRQ (LTE only) as reported by modem (unconverted)</field>
  272. </message>
  273. <message id="214" name="SATCOM_LINK_STATUS">
  274. <description>Status of the SatCom link</description>
  275. <field type="uint64_t" name="timestamp" units="us">Timestamp</field>
  276. <field type="uint64_t" name="last_heartbeat" units="us">Timestamp of the last successful sbd session</field>
  277. <field type="uint16_t" name="failed_sessions">Number of failed sessions</field>
  278. <field type="uint16_t" name="successful_sessions">Number of successful sessions</field>
  279. <field type="uint8_t" name="signal_quality">Signal quality</field>
  280. <field type="uint8_t" name="ring_pending">Ring call pending</field>
  281. <field type="uint8_t" name="tx_session_pending">Transmission session pending</field>
  282. <field type="uint8_t" name="rx_session_pending">Receiving session pending</field>
  283. </message>
  284. </messages>
  285. </mavlink>