-
Notifications
You must be signed in to change notification settings - Fork 28
/
Copy pathmavlink_standard_messages.xml
365 lines (321 loc) · 21.8 KB
/
mavlink_standard_messages.xml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
<?xml version="1.0"?>
<mavlink>
<messages>
<message name="HEARTBEAT" id="0">
The heartbeat message just shows that a system is present.
<field name="type" type="uint8_t">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field name="autopilot" type="uint8_t">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field>
</message>
<message name="BOOT" id="1">
<field name="version" type="uint32_t">The onboard software version</field>
</message>
<message name="SYSTEM_TIME" id="2">
The system time is the time of the master clock, typically the computer clock of the main onboard computer.
<field name="time_usec" type="uint64_t">Timestamp of the master clock in microseconds since UNIX epoch.</field>
</message>
<message name="PING" id="3">
A ping message either requesting or responding to a ping.
<field name="seq" type="uint32_t">PING sequence</field>
<field name="target_system" type="uint8_t">0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system</field>
<field name="target_component" type="uint8_t">0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system</field>
<field name="time" type="uint64_t">Unix timestamp in microseconds</field>
</message>
<message name="ACTION" id="10">
<field name="target" type="uint8_t">The system executing the action</field>
<field name="action" type="uint8_t">The action id</field>
</message>
<message name="SET_MODE" id="11">
Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h
<field name="target" type="uint8_t">The system setting the mode</field>
<field name="mode" type="uint8_t">The new mode</field>
</message>
<message name="SET_NAV_MODE" id="12">
Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h
<field name="target" type="uint8_t">The system setting the mode</field>
<field name="nav_mode" type="uint8_t">The new navigation mode</field>
</message>
<message name="PARAM_REQUEST_READ" id="20">
Request to read the onboard parameters.
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="param_id" type="array[15]">Onboard parameter id</field>
</message>
<message name="PARAM_REQUEST_LIST" id="21">
Request all parameters of this component.
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
</message>
<message name="PARAM_VALUE" id="22">
Emit the value of a onboard parameter.
<field name="param_id" type="array[15]">Onboard parameter id</field>
<field name="param_value" type="float">Onboard parameter value</field>
</message>
<message name="PARAM_SET" id="23">
Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot.
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="param_id" type="array[15]">Onboard parameter id</field>
<field name="param_value" type="float">Onboard parameter value</field>
</message>
<message name="PARAM_WRITE_STORAGE" id="24">
Set the current parameter value (currently active in RAM) PERMANTLY to EEPROM/HDD. It will be the new default value.
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
</message>
<message name="PID_SET" id="25">
Set PID values.
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="pid_id" type="uint8_t">PID ID</field>
<field name="k_p" type="float">P</field>
<field name="k_i" type="float">I</field>
<field name="k_d" type="float">D</field>
</message>
<message name="RAW_IMU" id="28">
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
<field name="xacc" type="int16_t">X acceleration (mg raw)</field>
<field name="yacc" type="int16_t">Y acceleration (mg raw)</field>
<field name="zacc" type="int16_t">Z acceleration (mg raw)</field>
<field name="xgyro" type="uint16_t">Angular speed around X axis (adc units)</field>
<field name="ygyro" type="uint16_t">Angular speed around Y axis (adc units)</field>
<field name="zgyro" type="uint16_t">Angular speed around Z axis (adc units)</field>
<field name="xmag" type="int16_t">X Magnetic field (milli tesla)</field>
<field name="ymag" type="int16_t">Y Magnetic field (milli tesla)</field>
<field name="zmag" type="int16_t">Z Magnetic field (milli tesla)</field>
</message>
<message name="RAW_PRESSURE" id="29">
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
<field name="press_abs" type="int32_t">Absolute pressure (hectopascal)</field>
<field name="press_diff1" type="int32_t">Differential pressure 1 (hectopascal)</field>
<field name="press_diff2" type="int32_t">Differential pressure 2 (hectopascal)</field>
</message>
<message name="ATTITUDE" id="30">
The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).
<field name="usec" type="uint64_t">Timestamp (microseconds)</field>
<field name="roll" type="float">Roll angle (rad)</field>
<field name="pitch" type="float">Pitch angle (rad)</field>
<field name="yaw" type="float">Yaw angle (rad)</field>
<field name="rollspeed" type="float">Roll angular speed (rad/s)</field>
<field name="pitchspeed" type="float">Pitch angular speed (rad/s)</field>
<field name="yawspeed" type="float">Yaw angular speed (rad/s)</field>
</message>
<message name="LOCAL_POSITION" id="31">
The filtered local position (e.g. fused computer vision and accelerometers).
<field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<field name="x" type="float">X Position</field>
<field name="y" type="float">Y Position</field>
<field name="z" type="float">Z Position</field>
<field name="vx" type="float">X Speed</field>
<field name="vy" type="float">Y Speed</field>
<field name="vz" type="float">Z Speed</field>
</message>
<message name="GPS_RAW" id="32">
The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate.
<field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<field name="fix_type" type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix</field>
<field name="lat" type="float">X Position</field>
<field name="lon" type="float">Y Position</field>
<field name="alt" type="float">Z Position in meters</field>
<field name="eph" type="float">Uncertainty in meters of latitude</field>
<field name="epv" type="float">Uncertainty in meters of longitude</field>
<field name="v" type="float">Overall speed</field>
<field name="hdg" type="float">Heading, in FIXME</field>
</message>
<message name="GPS_STATUS" id="27">
The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate.
<field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<field name="satellites_visible" type="uint8_t">Number of satellites visible</field>
<field name="satellite_prn" type="array[20]">Global satellite ID</field>
<field name="satellite_used" type="array[20]">0: Satellite not used, 1: used for localization</field>
<field name="satellite_elevation" type="array[20]">Elevation (0: right on top of receiver, 90: on the horizon) of satellite</field>
<field name="satellite_azimuth" type="array[20]">Direction of satellite, 0: 0 deg, 255: 360 deg.</field>
<field name="satellite_snr" type="array[20]">Signal to noise ratio of satellite</field>
</message>
<message name="GLOBAL_POSITION" id="33">
The filtered global position (e.g. fused GPS and accelerometers).
<field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<field name="lat" type="float">X Position</field>
<field name="lon" type="float">Y Position</field>
<field name="alt" type="float">Z Position</field>
<field name="vx" type="float">X Speed</field>
<field name="vy" type="float">Y Speed</field>
<field name="vz" type="float">Z Speed</field>
</message>
<message name="SYS_STATUS" id="34">
<field name="mode" type="uint8_t">System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h</field>
<field name="nav_mode" type="uint8_t">Navigation mode, see MAV_NAV_MODE ENUM</field>
<field name="status" type="uint8_t">System status flag, see MAV_STATUS ENUM</field>
<field name="vbat" type="uint16_t">Battery voltage, in millivolts</field>
<field name="motor_block" type="uint8_t">Motor block status flag</field>
<field name="packet_drop" type="uint16_t">Dropped packets</field>
</message>
<message name="RC_CHANNELS_RAW" id="35">
The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.
<field name="chan1" type="uint16_t">RC channel 1 value, in microseconds</field>
<field name="chan2" type="uint16_t">RC channel 2 value, in microseconds</field>
<field name="chan3" type="uint16_t">RC channel 3 value, in microseconds</field>
<field name="chan4" type="uint16_t">RC channel 3 value, in microseconds</field>
<field name="chan5" type="uint16_t">RC channel 3 value, in microseconds</field>
</message>
<message name="RC_CHANNELS_TRIM_SET" id="36">
Trim values to scale the RAW RC channel values. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.
<field name="chan1_min" type="uint16_t">RC channel 1 min value, in microseconds</field>
<field name="chan1_zero" type="uint16_t">RC channel 1 zero value, in microseconds</field>
<field name="chan1_max" type="uint16_t">RC channel 1 max value, in microseconds</field>
<field name="chan2_min" type="uint16_t">RC channel 2 min value, in microseconds</field>
<field name="chan2_zero" type="uint16_t">RC channel 2 zero value, in microseconds</field>
<field name="chan2_max" type="uint16_t">RC channel 2 max value, in microseconds</field>
<field name="chan3_min" type="uint16_t">RC channel 3 min value, in microseconds</field>
<field name="chan3_zero" type="uint16_t">RC channel 3 zero value, in microseconds</field>
<field name="chan3_max" type="uint16_t">RC channel 3 max value, in microseconds</field>
<field name="chan4_min" type="uint16_t">RC channel 4 min value, in microseconds</field>
<field name="chan4_zero" type="uint16_t">RC channel 4 zero value, in microseconds</field>
<field name="chan4_max" type="uint16_t">RC channel 4 max value, in microseconds</field>
<field name="chan5_min" type="uint16_t">RC channel 5 min value, in microseconds</field>
<field name="chan5_zero" type="uint16_t">RC channel 5 zero value, in microseconds</field>
<field name="chan5_max" type="uint16_t">RC channel 5 max value, in microseconds</field>
</message>
<message name="RC_CHANNELS_MAPPING" id="37">
Mapping defining which functions each RC channel has
<field name="chan1_function" type="uint8_t">RC channel 1 function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h</field>
<field name="chan2_function" type="uint8_t">RC channel 2 function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h</field>
<field name="chan3_function" type="uint8_t">RC channel 3 function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h</field>
<field name="chan4_function" type="uint8_t">RC channel 4 function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h</field>
<field name="chan5_function" type="uint8_t">RC channel 5 function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h</field>
</message>
<message name="RC_CHANNELS_MAPPING_SET" id="38">
Mapping defining which functions each RC channel has.
<field name="target_system" type="uint8_t">System ID</field>
<field name="chan1_function" type="uint8_t">RC channel 1 function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h</field>
<field name="chan2_function" type="uint8_t">RC channel 2 function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h</field>
<field name="chan3_function" type="uint8_t">RC channel 3 function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h</field>
<field name="chan4_function" type="uint8_t">RC channel 4 function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h</field>
<field name="chan5_function" type="uint8_t">RC channel 5 function, as defined in ENUM MAVLINK_RC_CHAN_MAPPING in mavlink/include/mavlink_types.h</field>
</message>
<message name="WAYPOINT" id="39">
Message encoding a waypoint. This message is emitted to announce
the presence of a waypoint. It cannot be used to set a waypoint, use WAYPOINT_SET for this purpose. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon. The global and body frame are related as: positive Z-down, positive X(front looking north, positive Y(body:right) looking east. Therefore x encodes in global mode the latitude, whereas y encodes the longitude and z the altitude over ground.
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="seq" type="uint16_t">Sequence</field>
<field name="type" type="uint8_t">0: global (GPS), 1: local, 2: global orbit, 3: local orbit</field>
<field name="orbit" type="uint8_t">Orbit to circle around the waypoint, in meters</field>
<field name="current" type="uint8_t">false:0, true:1</field>
<field name="x" type="float">local: x position, global: latitude</field>
<field name="y" type="float">y position: global: longitude</field>
<field name="z" type="float">z position: global: altitude</field>
<field name="yaw" type="float">yaw orientation in radians, 0 = NORTH</field>
<field name="autocontinue" type="uint16_t">autocontinue to next wp</field>
</message>
<message name="WAYPOINT_SET" id="40">
Message setting a waypoint. This message is emitted to announce
the presence of a waypoint. It cannot be used to set a waypoint, use WAYPOINT_SET for this purpose. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon. The global and body frame are related as: positive Z-down, positive X(front looking north, positive Y(body:right) looking east. Therefore x encodes in global mode the latitude, whereas y encodes the longitude and z the altitude over ground.
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="seq" type="uint16_t">Sequence</field>
<field name="type" type="uint8_t">0: global (GPS), 1: local, 2: global orbit, 3: local orbit</field>
<field name="orbit" type="uint8_t">Orbit to circle around the waypoint, in meters</field>
<field name="current" type="uint8_t">false:0, true:1</field>
<field name="x" type="float">local: x position, global: latitude</field>
<field name="y" type="float">y position: global: longitude</field>
<field name="z" type="float">z position: global: altitude</field>
<field name="yaw" type="float">yaw orientation in radians, 0 = NORTH</field>
<field name="autocontinue" type="uint16_t">autocontinue to next wp</field>
</message>
<message name="WAYPOINT_REQUEST" id="41">
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="seq" type="uint16_t">Sequence</field>
</message>
<message name="WAYPOINT_SET_CURRENT" id="42">
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="seq" type="uint16_t">Sequence</field>
</message>
<message name="WAYPOINT_REQUEST_LIST" id="43">
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
</message>
<message name="WAYPOINT_COUNT" id="44">
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="count" type="uint16_t">Number of Waypoints in the Sequence</field>
</message>
<message name="WAYPOINT_CLEAR_ALL" id="45">
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
</message>
<message name="WAYPOINT_REACHED" id="46">
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="seq" type="uint16_t">Sequence</field>
</message>
<message name="WAYPOINT_ERROR" id="47">
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="type" type="uint8_t">0: OK, 1: Error</field>
</message>
<message name="WAYPOINT_SET_GLOBAL_REFERENCE" id="48">
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="global_x" type="float">global x position</field>
<field name="global_y" type="float">global y position</field>
<field name="global_z" type="float">global z position</field>
<field name="global_yaw" type="float">global yaw orientation in radians, 0 = NORTH</field>
<field name="local_x" type="float">local x position that matches the global x position</field>
<field name="local_y" type="float">local y position that matches the global y position</field>
<field name="local_z" type="float">local z position that matches the global z position</field>
<field name="local_yaw" type="float">local yaw that matches the global yaw orientation</field>
</message>
<message name="SAFETY_SET_ALLOWED_AREA" id="49">
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="type" type="uint8_t">0: global, 1: local</field>
<field name="x1" type="float">x position 1</field>
<field name="y1" type="float">y position 1</field>
<field name="z1" type="float">z position 1</field>
<field name="x2" type="float">x position 2</field>
<field name="y2" type="float">y position 2</field>
<field name="z2" type="float">z position 2</field>
</message>
<message name="LOCAL_POSITION_SETPOINT_SET" id="50">
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="x" type="float">x position 1</field>
<field name="y" type="float">y position 1</field>
<field name="z" type="float">z position 1</field>
<field name="yaw" type="float">x position 2</field>
</message>
<message name="LOCAL_POSITION_SETPOINT" id="51">
<field name="x" type="float">x position 1</field>
<field name="y" type="float">y position 1</field>
<field name="z" type="float">z position 1</field>
<field name="yaw" type="float">x position 2</field>
</message>
<message name="ATTITUDE_CONTROLLER_OUTPUT" id="60">
<field name="enabled" type="uint8_t">1: enabled, 0: disabled</field>
<field name="roll" type="int8_t">Attitude roll: -128: -100%, 127: +100%</field>
<field name="pitch" type="int8_t">Attitude pitch: -128: -100%, 127: +100%</field>
<field name="yaw" type="int8_t">Attitude yaw: -128: -100%, 127: +100%</field>
<field name="thrust" type="int8_t">Attitude thrust: -128: -100%, 127: +100%</field>
</message>
<message name="POSITION_CONTROLLER_OUTPUT" id="61">
<field name="enabled" type="uint8_t">1: enabled, 0: disabled</field>
<field name="x" type="int8_t">Position x: -128: -100%, 127: +100%</field>
<field name="y" type="int8_t">Position y: -128: -100%, 127: +100%</field>
<field name="z" type="int8_t">Position z: -128: -100%, 127: +100%</field>
<field name="yaw" type="int8_t">Position yaw: -128: -100%, 127: +100%</field>
</message>
<!-- MESSAGE IDs 50 - 250: Space for custom messages in individual projectname_messages.xml files -->
<message name="STATUSTEXT" id= "254">
<field name="severity" type="uint8_t">Severity of status, 0 = info message, 255 = critical fault</field>
<field name="text" type="array[50]">Status text message, without null termination character</field>
</message>
<message name="DEBUG" id="255">
<field name="ind" type="uint8_t">index of debug variable</field>
<field name="value" type="float">DEBUG value</field>
</message>
</messages>
</mavlink>