Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | <?xml version='1.0'?> |
2 | <mavlink> |
||
3 | <version>2</version> |
||
4 | <enums> |
||
5 | <enum name="MAV_CMD"> |
||
6 | <description>Commands to be executed by the MAV. They can be executed on user request, |
||
7 | or as part of a mission script. If the action is used in a mission, the parameter mapping |
||
8 | to the waypoint/mission message is as follows: |
||
9 | Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what |
||
10 | ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data.</description> |
||
11 | <entry value="16" name="MAV_CMD_NAV_WAYPOINT"> |
||
12 | <description>Navigate to waypoint.</description> |
||
13 | <param index="1">Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)</param> |
||
14 | <param index="2">Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached)</param> |
||
15 | <param index="3">0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.</param> |
||
16 | <param index="4">Desired yaw angle at waypoint (rotary wing)</param> |
||
17 | <param index="5">Latitude</param> |
||
18 | <param index="6">Longitude</param> |
||
19 | <param index="7">Altitude</param> |
||
20 | </entry> |
||
21 | <entry value="17" name="MAV_CMD_NAV_LOITER_UNLIM"> |
||
22 | <description>Loiter around this waypoint an unlimited amount of time</description> |
||
23 | <param index="1">Empty</param> |
||
24 | <param index="2">Empty</param> |
||
25 | <param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param> |
||
26 | <param index="4">Desired yaw angle.</param> |
||
27 | <param index="5">Latitude</param> |
||
28 | <param index="6">Longitude</param> |
||
29 | <param index="7">Altitude</param> |
||
30 | </entry> |
||
31 | <entry value="18" name="MAV_CMD_NAV_LOITER_TURNS"> |
||
32 | <description>Loiter around this waypoint for X turns</description> |
||
33 | <param index="1">Turns</param> |
||
34 | <param index="2">Empty</param> |
||
35 | <param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param> |
||
36 | <param index="4">Desired yaw angle.</param> |
||
37 | <param index="5">Latitude</param> |
||
38 | <param index="6">Longitude</param> |
||
39 | <param index="7">Altitude</param> |
||
40 | </entry> |
||
41 | <entry value="19" name="MAV_CMD_NAV_LOITER_TIME"> |
||
42 | <description>Loiter around this waypoint for X seconds</description> |
||
43 | <param index="1">Seconds (decimal)</param> |
||
44 | <param index="2">Empty</param> |
||
45 | <param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param> |
||
46 | <param index="4">Desired yaw angle.</param> |
||
47 | <param index="5">Latitude</param> |
||
48 | <param index="6">Longitude</param> |
||
49 | <param index="7">Altitude</param> |
||
50 | </entry> |
||
51 | <entry value="20" name="MAV_CMD_NAV_RETURN_TO_LAUNCH"> |
||
52 | <description>Return to launch location</description> |
||
53 | <param index="1">Empty</param> |
||
54 | <param index="2">Empty</param> |
||
55 | <param index="3">Empty</param> |
||
56 | <param index="4">Empty</param> |
||
57 | <param index="5">Empty</param> |
||
58 | <param index="6">Empty</param> |
||
59 | <param index="7">Empty</param> |
||
60 | </entry> |
||
61 | <entry value="21" name="MAV_CMD_NAV_LAND"> |
||
62 | <description>Land at location</description> |
||
63 | <param index="1">Empty</param> |
||
64 | <param index="2">Empty</param> |
||
65 | <param index="3">Empty</param> |
||
66 | <param index="4">Desired yaw angle.</param> |
||
67 | <param index="5">Latitude</param> |
||
68 | <param index="6">Longitude</param> |
||
69 | <param index="7">Altitude</param> |
||
70 | </entry> |
||
71 | <entry value="22" name="MAV_CMD_NAV_TAKEOFF"> |
||
72 | <description>Takeoff from ground / hand</description> |
||
73 | <param index="1">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param> |
||
74 | <param index="2">Empty</param> |
||
75 | <param index="3">Empty</param> |
||
76 | <param index="4">Yaw angle (if magnetometer present), ignored without magnetometer</param> |
||
77 | <param index="5">Latitude</param> |
||
78 | <param index="6">Longitude</param> |
||
79 | <param index="7">Altitude</param> |
||
80 | </entry> |
||
81 | <entry value="80" name="MAV_CMD_NAV_ROI"> |
||
82 | <description>Sets the region of interest (ROI) for a sensor set or the |
||
83 | vehicle itself. This can then be used by the vehicles control |
||
84 | system to control the vehicle attitude and the attitude of various |
||
85 | sensors such as cameras.</description> |
||
86 | <param index="1">Region of intereset mode. (see MAV_ROI enum)</param> |
||
87 | <param index="2">Waypoint index/ target ID. (see MAV_ROI enum)</param> |
||
88 | <param index="3">ROI index (allows a vehicle to manage multiple ROI's)</param> |
||
89 | <param index="4">Empty</param> |
||
90 | <param index="5">x the location of the fixed ROI (see MAV_FRAME)</param> |
||
91 | <param index="6">y</param> |
||
92 | <param index="7">z</param> |
||
93 | </entry> |
||
94 | <entry value="81" name="MAV_CMD_NAV_PATHPLANNING"> |
||
95 | <description>Control autonomous path planning on the MAV.</description> |
||
96 | <param index="1">0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning</param> |
||
97 | <param index="2">0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid</param> |
||
98 | <param index="3">Empty</param> |
||
99 | <param index="4">Yaw angle at goal, in compass degrees, [0..360]</param> |
||
100 | <param index="5">Latitude/X of goal</param> |
||
101 | <param index="6">Longitude/Y of goal</param> |
||
102 | <param index="7">Altitude/Z of goal</param> |
||
103 | </entry> |
||
104 | <entry value="95" name="MAV_CMD_NAV_LAST"> |
||
105 | <description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description> |
||
106 | <param index="1">Empty</param> |
||
107 | <param index="2">Empty</param> |
||
108 | <param index="3">Empty</param> |
||
109 | <param index="4">Empty</param> |
||
110 | <param index="5">Empty</param> |
||
111 | <param index="6">Empty</param> |
||
112 | <param index="7">Empty</param> |
||
113 | </entry> |
||
114 | <entry value="112" name="MAV_CMD_CONDITION_DELAY"> |
||
115 | <description>Delay mission state machine.</description> |
||
116 | <param index="1">Delay in seconds (decimal)</param> |
||
117 | <param index="2">Empty</param> |
||
118 | <param index="3">Empty</param> |
||
119 | <param index="4">Empty</param> |
||
120 | <param index="5">Empty</param> |
||
121 | <param index="6">Empty</param> |
||
122 | <param index="7">Empty</param> |
||
123 | </entry> |
||
124 | <entry value="113" name="MAV_CMD_CONDITION_CHANGE_ALT"> |
||
125 | <description>Ascend/descend at rate. Delay mission state machine until desired altitude reached.</description> |
||
126 | <param index="1">Descent / Ascend rate (m/s)</param> |
||
127 | <param index="2">Empty</param> |
||
128 | <param index="3">Empty</param> |
||
129 | <param index="4">Empty</param> |
||
130 | <param index="5">Empty</param> |
||
131 | <param index="6">Empty</param> |
||
132 | <param index="7">Finish Altitude</param> |
||
133 | </entry> |
||
134 | <entry value="114" name="MAV_CMD_CONDITION_DISTANCE"> |
||
135 | <description>Delay mission state machine until within desired distance of next NAV point.</description> |
||
136 | <param index="1">Distance (meters)</param> |
||
137 | <param index="2">Empty</param> |
||
138 | <param index="3">Empty</param> |
||
139 | <param index="4">Empty</param> |
||
140 | <param index="5">Empty</param> |
||
141 | <param index="6">Empty</param> |
||
142 | <param index="7">Empty</param> |
||
143 | </entry> |
||
144 | <entry value="115" name="MAV_CMD_CONDITION_YAW"> |
||
145 | <description>Reach a certain target angle.</description> |
||
146 | <param index="1">target angle: [0-360], 0 is north</param> |
||
147 | <param index="2">speed during yaw change:[deg per second]</param> |
||
148 | <param index="3">direction: negative: counter clockwise, positive: clockwise [-1,1]</param> |
||
149 | <param index="4">relative offset or absolute angle: [ 1,0]</param> |
||
150 | <param index="5">Empty</param> |
||
151 | <param index="6">Empty</param> |
||
152 | <param index="7">Empty</param> |
||
153 | </entry> |
||
154 | <entry value="159" name="MAV_CMD_CONDITION_LAST"> |
||
155 | <description>NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration</description> |
||
156 | <param index="1">Empty</param> |
||
157 | <param index="2">Empty</param> |
||
158 | <param index="3">Empty</param> |
||
159 | <param index="4">Empty</param> |
||
160 | <param index="5">Empty</param> |
||
161 | <param index="6">Empty</param> |
||
162 | <param index="7">Empty</param> |
||
163 | </entry> |
||
164 | <entry value="176" name="MAV_CMD_DO_SET_MODE"> |
||
165 | <description>Set system mode.</description> |
||
166 | <param index="1">Mode, as defined by ENUM MAV_MODE</param> |
||
167 | <param index="2">Empty</param> |
||
168 | <param index="3">Empty</param> |
||
169 | <param index="4">Empty</param> |
||
170 | <param index="5">Empty</param> |
||
171 | <param index="6">Empty</param> |
||
172 | <param index="7">Empty</param> |
||
173 | </entry> |
||
174 | <entry value="177" name="MAV_CMD_DO_JUMP"> |
||
175 | <description>Jump to the desired command in the mission list. Repeat this action only the specified number of times</description> |
||
176 | <param index="1">Sequence number</param> |
||
177 | <param index="2">Repeat count</param> |
||
178 | <param index="3">Empty</param> |
||
179 | <param index="4">Empty</param> |
||
180 | <param index="5">Empty</param> |
||
181 | <param index="6">Empty</param> |
||
182 | <param index="7">Empty</param> |
||
183 | </entry> |
||
184 | <entry value="178" name="MAV_CMD_DO_CHANGE_SPEED"> |
||
185 | <description>Change speed and/or throttle set points.</description> |
||
186 | <param index="1">Speed type (0=Airspeed, 1=Ground Speed)</param> |
||
187 | <param index="2">Speed (m/s, -1 indicates no change)</param> |
||
188 | <param index="3">Throttle ( Percent, -1 indicates no change)</param> |
||
189 | <param index="4">Empty</param> |
||
190 | <param index="5">Empty</param> |
||
191 | <param index="6">Empty</param> |
||
192 | <param index="7">Empty</param> |
||
193 | </entry> |
||
194 | <entry value="179" name="MAV_CMD_DO_SET_HOME"> |
||
195 | <description>Changes the home location either to the current location or a specified location.</description> |
||
196 | <param index="1">Use current (1=use current location, 0=use specified location)</param> |
||
197 | <param index="2">Empty</param> |
||
198 | <param index="3">Empty</param> |
||
199 | <param index="4">Empty</param> |
||
200 | <param index="5">Latitude</param> |
||
201 | <param index="6">Longitude</param> |
||
202 | <param index="7">Altitude</param> |
||
203 | </entry> |
||
204 | <entry value="180" name="MAV_CMD_DO_SET_PARAMETER"> |
||
205 | <description>Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.</description> |
||
206 | <param index="1">Parameter number</param> |
||
207 | <param index="2">Parameter value</param> |
||
208 | <param index="3">Empty</param> |
||
209 | <param index="4">Empty</param> |
||
210 | <param index="5">Empty</param> |
||
211 | <param index="6">Empty</param> |
||
212 | <param index="7">Empty</param> |
||
213 | </entry> |
||
214 | <entry value="181" name="MAV_CMD_DO_SET_RELAY"> |
||
215 | <description>Set a relay to a condition.</description> |
||
216 | <param index="1">Relay number</param> |
||
217 | <param index="2">Setting (1=on, 0=off, others possible depending on system hardware)</param> |
||
218 | <param index="3">Empty</param> |
||
219 | <param index="4">Empty</param> |
||
220 | <param index="5">Empty</param> |
||
221 | <param index="6">Empty</param> |
||
222 | <param index="7">Empty</param> |
||
223 | </entry> |
||
224 | <entry value="182" name="MAV_CMD_DO_REPEAT_RELAY"> |
||
225 | <description>Cycle a relay on and off for a desired number of cyles with a desired period.</description> |
||
226 | <param index="1">Relay number</param> |
||
227 | <param index="2">Cycle count</param> |
||
228 | <param index="3">Cycle time (seconds, decimal)</param> |
||
229 | <param index="4">Empty</param> |
||
230 | <param index="5">Empty</param> |
||
231 | <param index="6">Empty</param> |
||
232 | <param index="7">Empty</param> |
||
233 | </entry> |
||
234 | <entry value="183" name="MAV_CMD_DO_SET_SERVO"> |
||
235 | <description>Set a servo to a desired PWM value.</description> |
||
236 | <param index="1">Servo number</param> |
||
237 | <param index="2">PWM (microseconds, 1000 to 2000 typical)</param> |
||
238 | <param index="3">Empty</param> |
||
239 | <param index="4">Empty</param> |
||
240 | <param index="5">Empty</param> |
||
241 | <param index="6">Empty</param> |
||
242 | <param index="7">Empty</param> |
||
243 | </entry> |
||
244 | <entry value="184" name="MAV_CMD_DO_REPEAT_SERVO"> |
||
245 | <description>Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.</description> |
||
246 | <param index="1">Servo number</param> |
||
247 | <param index="2">PWM (microseconds, 1000 to 2000 typical)</param> |
||
248 | <param index="3">Cycle count</param> |
||
249 | <param index="4">Cycle time (seconds)</param> |
||
250 | <param index="5">Empty</param> |
||
251 | <param index="6">Empty</param> |
||
252 | <param index="7">Empty</param> |
||
253 | </entry> |
||
254 | <entry value="200" name="MAV_CMD_DO_CONTROL_VIDEO"> |
||
255 | <description>Control onboard camera capturing.</description> |
||
256 | <param index="1">Camera ID (-1 for all)</param> |
||
257 | <param index="2">Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw</param> |
||
258 | <param index="3">Transmission mode: 0: video stream, >0: single images every n seconds (decimal)</param> |
||
259 | <param index="4">Recording: 0: disabled, 1: enabled compressed, 2: enabled raw</param> |
||
260 | <param index="5">Empty</param> |
||
261 | <param index="6">Empty</param> |
||
262 | <param index="7">Empty</param> |
||
263 | </entry> |
||
264 | <entry value="201" name="MAV_CMD_DO_SET_ROI"> |
||
265 | <description>Sets the region of interest (ROI) for a sensor set or the |
||
266 | vehicle itself. This can then be used by the vehicles control |
||
267 | system to control the vehicle attitude and the attitude of various |
||
268 | devices such as cameras. |
||
269 | </description> |
||
270 | <param index="1">Region of interest mode. (see MAV_ROI enum)</param> |
||
271 | <param index="2">Waypoint index/ target ID. (see MAV_ROI enum)</param> |
||
272 | <param index="3">ROI index (allows a vehicle to manage multiple cameras etc.)</param> |
||
273 | <param index="4">Empty</param> |
||
274 | <param index="5">x the location of the fixed ROI (see MAV_FRAME)</param> |
||
275 | <param index="6">y</param> |
||
276 | <param index="7">z</param> |
||
277 | </entry> |
||
278 | <entry value="240" name="MAV_CMD_DO_LAST"> |
||
279 | <description>NOP - This command is only used to mark the upper limit of the DO commands in the enumeration</description> |
||
280 | <param index="1">Empty</param> |
||
281 | <param index="2">Empty</param> |
||
282 | <param index="3">Empty</param> |
||
283 | <param index="4">Empty</param> |
||
284 | <param index="5">Empty</param> |
||
285 | <param index="6">Empty</param> |
||
286 | <param index="7">Empty</param> |
||
287 | </entry> |
||
288 | <entry value="241" name="MAV_CMD_PREFLIGHT_CALIBRATION"> |
||
289 | <description>Trigger calibration. This command will be only accepted if in pre-flight mode.</description> |
||
290 | <param index="1">Gyro calibration: 0: no, 1: yes</param> |
||
291 | <param index="2">Magnetometer calibration: 0: no, 1: yes</param> |
||
292 | <param index="3">Ground pressure: 0: no, 1: yes</param> |
||
293 | <param index="4">Radio calibration: 0: no, 1: yes</param> |
||
294 | <param index="5">Empty</param> |
||
295 | <param index="6">Empty</param> |
||
296 | <param index="7">Empty</param> |
||
297 | </entry> |
||
298 | <entry value="245" name="MAV_CMD_PREFLIGHT_STORAGE"> |
||
299 | <description>Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.</description> |
||
300 | <param index="1">Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param> |
||
301 | <param index="2">Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param> |
||
302 | <param index="3">Reserved</param> |
||
303 | <param index="4">Reserved</param> |
||
304 | <param index="5">Empty</param> |
||
305 | <param index="6">Empty</param> |
||
306 | <param index="7">Empty</param> |
||
307 | </entry> |
||
308 | </enum> |
||
309 | <enum name="MAV_DATA_STREAM"> |
||
310 | <description>Data stream IDs. A data stream is not a fixed set of messages, but rather a |
||
311 | recommendation to the autopilot software. Individual autopilots may or may not obey |
||
312 | the recommended messages. |
||
313 | </description> |
||
314 | <entry value="0" name="MAV_DATA_STREAM_ALL"> |
||
315 | <description>Enable all data streams</description> |
||
316 | </entry> |
||
317 | <entry value="1" name="MAV_DATA_STREAM_RAW_SENSORS"> |
||
318 | <description>Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.</description> |
||
319 | </entry> |
||
320 | <entry value="2" name="MAV_DATA_STREAM_EXTENDED_STATUS"> |
||
321 | <description>Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS</description> |
||
322 | </entry> |
||
323 | <entry value="3" name="MAV_DATA_STREAM_RC_CHANNELS"> |
||
324 | <description>Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW</description> |
||
325 | </entry> |
||
326 | <entry value="4" name="MAV_DATA_STREAM_RAW_CONTROLLER"> |
||
327 | <description>Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.</description> |
||
328 | </entry> |
||
329 | <entry value="6" name="MAV_DATA_STREAM_POSITION"> |
||
330 | <description>Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.</description> |
||
331 | </entry> |
||
332 | <entry value="10" name="MAV_DATA_STREAM_EXTRA1"> |
||
333 | <description>Dependent on the autopilot</description> |
||
334 | </entry> |
||
335 | <entry value="11" name="MAV_DATA_STREAM_EXTRA2"> |
||
336 | <description>Dependent on the autopilot</description> |
||
337 | </entry> |
||
338 | <entry value="12" name="MAV_DATA_STREAM_EXTRA3"> |
||
339 | <description>Dependent on the autopilot</description> |
||
340 | </entry> |
||
341 | </enum> |
||
342 | <enum name="MAV_ROI"> |
||
343 | <description> The ROI (region of interest) for the vehicle. This can be |
||
344 | be used by the vehicle for camera/vehicle attitude alignment (see |
||
345 | MAV_CMD_NAV_ROI). |
||
346 | </description> |
||
347 | <entry value="0" name="MAV_ROI_NONE"> |
||
348 | <description>No region of interest.</description> |
||
349 | </entry> |
||
350 | <entry value="1" name="MAV_ROI_WPNEXT"> |
||
351 | <description>Point toward next waypoint.</description> |
||
352 | </entry> |
||
353 | <entry value="2" name="MAV_ROI_WPINDEX"> |
||
354 | <description>Point toward given waypoint.</description> |
||
355 | </entry> |
||
356 | <entry value="3" name="MAV_ROI_LOCATION"> |
||
357 | <description>Point toward fixed location.</description> |
||
358 | </entry> |
||
359 | <entry value="4" name="MAV_ROI_TARGET"> |
||
360 | <description>Point toward of given id.</description> |
||
361 | </entry> |
||
362 | </enum> |
||
363 | </enums> |
||
364 | <messages> |
||
365 | <message id="0" name="HEARTBEAT"> |
||
366 | <description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description> |
||
367 | <field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field> |
||
368 | <field type="uint8_t" name="autopilot">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field> |
||
369 | <field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version</field> |
||
370 | </message> |
||
371 | <message id="1" name="BOOT"> |
||
372 | <description>The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions.</description> |
||
373 | <field type="uint32_t" name="version">The onboard software version</field> |
||
374 | </message> |
||
375 | <message id="2" name="SYSTEM_TIME"> |
||
376 | <description>The system time is the time of the master clock, typically the computer clock of the main onboard computer.</description> |
||
377 | <field type="uint64_t" name="time_usec">Timestamp of the master clock in microseconds since UNIX epoch.</field> |
||
378 | </message> |
||
379 | <message id="3" name="PING"> |
||
380 | <description>A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.</description> |
||
381 | <field type="uint32_t" name="seq">PING sequence</field> |
||
382 | <field type="uint8_t" name="target_system">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> |
||
383 | <field type="uint8_t" name="target_component">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> |
||
384 | <field type="uint64_t" name="time">Unix timestamp in microseconds</field> |
||
385 | </message> |
||
386 | <message id="4" name="SYSTEM_TIME_UTC"> |
||
387 | <description>UTC date and time from GPS module</description> |
||
388 | <field type="uint32_t" name="utc_date">GPS UTC date ddmmyy</field> |
||
389 | <field type="uint32_t" name="utc_time">GPS UTC time hhmmss</field> |
||
390 | </message> |
||
391 | <message id="5" name="CHANGE_OPERATOR_CONTROL"> |
||
392 | <description>Request to control this MAV</description> |
||
393 | <field type="uint8_t" name="target_system">System the GCS requests control for</field> |
||
394 | <field type="uint8_t" name="control_request">0: request control of this MAV, 1: Release control of this MAV</field> |
||
395 | <field type="uint8_t" name="version">0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.</field> |
||
396 | <field type="char[25]" name="passkey">Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"</field> |
||
397 | </message> |
||
398 | <message id="6" name="CHANGE_OPERATOR_CONTROL_ACK"> |
||
399 | <description>Accept / deny control of this MAV</description> |
||
400 | <field type="uint8_t" name="gcs_system_id">ID of the GCS this message </field> |
||
401 | <field type="uint8_t" name="control_request">0: request control of this MAV, 1: Release control of this MAV</field> |
||
402 | <field type="uint8_t" name="ack">0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control</field> |
||
403 | </message> |
||
404 | <message id="7" name="AUTH_KEY"> |
||
405 | <description>Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.</description> |
||
406 | <field type="char[32]" name="key">key</field> |
||
407 | </message> |
||
408 | <message id="9" name="ACTION_ACK"> |
||
409 | <description>This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description> |
||
410 | <field type="uint8_t" name="action">The action id</field> |
||
411 | <field type="uint8_t" name="result">0: Action DENIED, 1: Action executed</field> |
||
412 | </message> |
||
413 | <message id="10" name="ACTION"> |
||
414 | <description>An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description> |
||
415 | <field type="uint8_t" name="target">The system executing the action</field> |
||
416 | <field type="uint8_t" name="target_component">The component executing the action</field> |
||
417 | <field type="uint8_t" name="action">The action id</field> |
||
418 | </message> |
||
419 | <message id="11" name="SET_MODE"> |
||
420 | <description>Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.</description> |
||
421 | <field type="uint8_t" name="target">The system setting the mode</field> |
||
422 | <field type="uint8_t" name="mode">The new mode</field> |
||
423 | </message> |
||
424 | <message id="12" name="SET_NAV_MODE"> |
||
425 | <description>Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h. The navigation mode applies to the whole aircraft and thus all components.</description> |
||
426 | <field type="uint8_t" name="target">The system setting the mode</field> |
||
427 | <field type="uint8_t" name="nav_mode">The new navigation mode</field> |
||
428 | </message> |
||
429 | <message id="20" name="PARAM_REQUEST_READ"> |
||
430 | <description>Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.</description> |
||
431 | <field type="uint8_t" name="target_system">System ID</field> |
||
432 | <field type="uint8_t" name="target_component">Component ID</field> |
||
433 | <field type="array[15]" name="param_id">Onboard parameter id</field> |
||
434 | <field type="int16_t" name="param_index">Parameter index. Send -1 to use the param ID field as identifier</field> |
||
435 | </message> |
||
436 | <message id="21" name="PARAM_REQUEST_LIST"> |
||
437 | <description>Request all parameters of this component. After his request, all parameters are emitted.</description> |
||
438 | <field type="uint8_t" name="target_system">System ID</field> |
||
439 | <field type="uint8_t" name="target_component">Component ID</field> |
||
440 | </message> |
||
441 | <message id="22" name="PARAM_VALUE"> |
||
442 | <description>Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.</description> |
||
443 | <field type="array[15]" name="param_id">Onboard parameter id</field> |
||
444 | <field type="float" name="param_value">Onboard parameter value</field> |
||
445 | <field type="uint16_t" name="param_count">Total number of onboard parameters</field> |
||
446 | <field type="uint16_t" name="param_index">Index of this onboard parameter</field> |
||
447 | </message> |
||
448 | <message id="23" name="PARAM_SET"> |
||
449 | <description>Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.</description> |
||
450 | <field type="uint8_t" name="target_system">System ID</field> |
||
451 | <field type="uint8_t" name="target_component">Component ID</field> |
||
452 | <field type="array[15]" name="param_id">Onboard parameter id</field> |
||
453 | <field type="float" name="param_value">Onboard parameter value</field> |
||
454 | </message> |
||
455 | <message id="25" name="GPS_RAW_INT"> |
||
456 | <description>The global position, as returned by the Global Positioning System (GPS). This is |
||
457 | NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description> |
||
458 | <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> |
||
459 | <field type="uint8_t" name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field> |
||
460 | <field type="int32_t" name="lat">Latitude in 1E7 degrees</field> |
||
461 | <field type="int32_t" name="lon">Longitude in 1E7 degrees</field> |
||
462 | <field type="int32_t" name="alt">Altitude in 1E3 meters (millimeters)</field> |
||
463 | <field type="float" name="eph">GPS HDOP</field> |
||
464 | <field type="float" name="epv">GPS VDOP</field> |
||
465 | <field type="float" name="v">GPS ground speed (m/s)</field> |
||
466 | <field type="float" name="hdg">Compass heading in degrees, 0..360 degrees</field> |
||
467 | </message> |
||
468 | <message id="26" name="SCALED_IMU"> |
||
469 | <description>The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units</description> |
||
470 | <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> |
||
471 | <field type="int16_t" name="xacc">X acceleration (mg)</field> |
||
472 | <field type="int16_t" name="yacc">Y acceleration (mg)</field> |
||
473 | <field type="int16_t" name="zacc">Z acceleration (mg)</field> |
||
474 | <field type="int16_t" name="xgyro">Angular speed around X axis (millirad /sec)</field> |
||
475 | <field type="int16_t" name="ygyro">Angular speed around Y axis (millirad /sec)</field> |
||
476 | <field type="int16_t" name="zgyro">Angular speed around Z axis (millirad /sec)</field> |
||
477 | <field type="int16_t" name="xmag">X Magnetic field (milli tesla)</field> |
||
478 | <field type="int16_t" name="ymag">Y Magnetic field (milli tesla)</field> |
||
479 | <field type="int16_t" name="zmag">Z Magnetic field (milli tesla)</field> |
||
480 | </message> |
||
481 | <message id="27" name="GPS_STATUS"> |
||
482 | <description>The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.</description> |
||
483 | <field type="uint8_t" name="satellites_visible">Number of satellites visible</field> |
||
484 | <field type="array[20]" name="satellite_prn">Global satellite ID</field> |
||
485 | <field type="array[20]" name="satellite_used">0: Satellite not used, 1: used for localization</field> |
||
486 | <field type="array[20]" name="satellite_elevation">Elevation (0: right on top of receiver, 90: on the horizon) of satellite</field> |
||
487 | <field type="array[20]" name="satellite_azimuth">Direction of satellite, 0: 0 deg, 255: 360 deg.</field> |
||
488 | <field type="array[20]" name="satellite_snr">Signal to noise ratio of satellite</field> |
||
489 | </message> |
||
490 | <message id="28" name="RAW_IMU"> |
||
491 | <description>The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.</description> |
||
492 | <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> |
||
493 | <field type="int16_t" name="xacc">X acceleration (raw)</field> |
||
494 | <field type="int16_t" name="yacc">Y acceleration (raw)</field> |
||
495 | <field type="int16_t" name="zacc">Z acceleration (raw)</field> |
||
496 | <field type="int16_t" name="xgyro">Angular speed around X axis (raw)</field> |
||
497 | <field type="int16_t" name="ygyro">Angular speed around Y axis (raw)</field> |
||
498 | <field type="int16_t" name="zgyro">Angular speed around Z axis (raw)</field> |
||
499 | <field type="int16_t" name="xmag">X Magnetic field (raw)</field> |
||
500 | <field type="int16_t" name="ymag">Y Magnetic field (raw)</field> |
||
501 | <field type="int16_t" name="zmag">Z Magnetic field (raw)</field> |
||
502 | </message> |
||
503 | <message id="29" name="RAW_PRESSURE"> |
||
504 | <description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.</description> |
||
505 | <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> |
||
506 | <field type="int16_t" name="press_abs">Absolute pressure (raw)</field> |
||
507 | <field type="int16_t" name="press_diff1">Differential pressure 1 (raw)</field> |
||
508 | <field type="int16_t" name="press_diff2">Differential pressure 2 (raw)</field> |
||
509 | <field type="int16_t" name="temperature">Raw Temperature measurement (raw)</field> |
||
510 | </message> |
||
511 | <message id="38" name="SCALED_PRESSURE"> |
||
512 | <description>The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.</description> |
||
513 | <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> |
||
514 | <field type="float" name="press_abs">Absolute pressure (hectopascal)</field> |
||
515 | <field type="float" name="press_diff">Differential pressure 1 (hectopascal)</field> |
||
516 | <field type="int16_t" name="temperature">Temperature measurement (0.01 degrees celsius)</field> |
||
517 | </message> |
||
518 | <message id="30" name="ATTITUDE"> |
||
519 | <description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).</description> |
||
520 | <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> |
||
521 | <field type="float" name="roll">Roll angle (rad)</field> |
||
522 | <field type="float" name="pitch">Pitch angle (rad)</field> |
||
523 | <field type="float" name="yaw">Yaw angle (rad)</field> |
||
524 | <field type="float" name="rollspeed">Roll angular speed (rad/s)</field> |
||
525 | <field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field> |
||
526 | <field type="float" name="yawspeed">Yaw angular speed (rad/s)</field> |
||
527 | </message> |
||
528 | <message id="31" name="LOCAL_POSITION"> |
||
529 | <description>The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame)</description> |
||
530 | <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> |
||
531 | <field type="float" name="x">X Position</field> |
||
532 | <field type="float" name="y">Y Position</field> |
||
533 | <field type="float" name="z">Z Position</field> |
||
534 | <field type="float" name="vx">X Speed</field> |
||
535 | <field type="float" name="vy">Y Speed</field> |
||
536 | <field type="float" name="vz">Z Speed</field> |
||
537 | </message> |
||
538 | <message id="33" name="GLOBAL_POSITION"> |
||
539 | <description>The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame)</description> |
||
540 | <field type="uint64_t" name="usec">Timestamp (microseconds since unix epoch)</field> |
||
541 | <field type="float" name="lat">Latitude, in degrees</field> |
||
542 | <field type="float" name="lon">Longitude, in degrees</field> |
||
543 | <field type="float" name="alt">Absolute altitude, in meters</field> |
||
544 | <field type="float" name="vx">X Speed (in Latitude direction, positive: going north)</field> |
||
545 | <field type="float" name="vy">Y Speed (in Longitude direction, positive: going east)</field> |
||
546 | <field type="float" name="vz">Z Speed (in Altitude direction, positive: going up)</field> |
||
547 | </message> |
||
548 | <message id="32" name="GPS_RAW"> |
||
549 | <description>The global position, as returned by the Global Positioning System (GPS). This is |
||
550 | NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description> |
||
551 | <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> |
||
552 | <field type="uint8_t" name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field> |
||
553 | <field type="float" name="lat">Latitude in degrees</field> |
||
554 | <field type="float" name="lon">Longitude in degrees</field> |
||
555 | <field type="float" name="alt">Altitude in meters</field> |
||
556 | <field type="float" name="eph">GPS HDOP</field> |
||
557 | <field type="float" name="epv">GPS VDOP</field> |
||
558 | <field type="float" name="v">GPS ground speed</field> |
||
559 | <field type="float" name="hdg">Compass heading in degrees, 0..360 degrees</field> |
||
560 | </message> |
||
561 | <message id="34" name="SYS_STATUS"> |
||
562 | <description>The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.</description> |
||
563 | <field type="uint8_t" name="mode">System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h</field> |
||
564 | <field type="uint8_t" name="nav_mode">Navigation mode, see MAV_NAV_MODE ENUM</field> |
||
565 | <field type="uint8_t" name="status">System status flag, see MAV_STATUS ENUM</field> |
||
566 | <field type="uint16_t" name="load">Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000</field> |
||
567 | <field type="uint16_t" name="vbat">Battery voltage, in millivolts (1 = 1 millivolt)</field> |
||
568 | <field type="uint16_t" name="battery_remaining">Remaining battery energy: (0%: 0, 100%: 1000)</field> |
||
569 | <field type="uint16_t" name="packet_drop">Dropped packets (packets that were corrupted on reception on the MAV)</field> |
||
570 | </message> |
||
571 | <message id="35" name="RC_CHANNELS_RAW"> |
||
572 | <description>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.</description> |
||
573 | <field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field> |
||
574 | <field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field> |
||
575 | <field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field> |
||
576 | <field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field> |
||
577 | <field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field> |
||
578 | <field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field> |
||
579 | <field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field> |
||
580 | <field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field> |
||
581 | <field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field> |
||
582 | </message> |
||
583 | <message id="36" name="RC_CHANNELS_SCALED"> |
||
584 | <description>The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000</description> |
||
585 | <field type="int16_t" name="chan1_scaled">RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> |
||
586 | <field type="int16_t" name="chan2_scaled">RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> |
||
587 | <field type="int16_t" name="chan3_scaled">RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> |
||
588 | <field type="int16_t" name="chan4_scaled">RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> |
||
589 | <field type="int16_t" name="chan5_scaled">RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> |
||
590 | <field type="int16_t" name="chan6_scaled">RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> |
||
591 | <field type="int16_t" name="chan7_scaled">RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> |
||
592 | <field type="int16_t" name="chan8_scaled">RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> |
||
593 | <field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field> |
||
594 | </message> |
||
595 | <message id="37" name="SERVO_OUTPUT_RAW"> |
||
596 | <description>The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.</description> |
||
597 | <field type="uint16_t" name="servo1_raw">Servo output 1 value, in microseconds</field> |
||
598 | <field type="uint16_t" name="servo2_raw">Servo output 2 value, in microseconds</field> |
||
599 | <field type="uint16_t" name="servo3_raw">Servo output 3 value, in microseconds</field> |
||
600 | <field type="uint16_t" name="servo4_raw">Servo output 4 value, in microseconds</field> |
||
601 | <field type="uint16_t" name="servo5_raw">Servo output 5 value, in microseconds</field> |
||
602 | <field type="uint16_t" name="servo6_raw">Servo output 6 value, in microseconds</field> |
||
603 | <field type="uint16_t" name="servo7_raw">Servo output 7 value, in microseconds</field> |
||
604 | <field type="uint16_t" name="servo8_raw">Servo output 8 value, in microseconds</field> |
||
605 | </message> |
||
606 | <message id="39" name="WAYPOINT"> |
||
607 | <description>Message encoding a waypoint. This message is emitted to announce |
||
608 | the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed</description> |
||
609 | <field type="uint8_t" name="target_system">System ID</field> |
||
610 | <field type="uint8_t" name="target_component">Component ID</field> |
||
611 | <field type="uint16_t" name="seq">Sequence</field> |
||
612 | <field type="uint8_t" name="frame">The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h</field> |
||
613 | <field type="uint8_t" name="command">The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs</field> |
||
614 | <field type="uint8_t" name="current">false:0, true:1</field> |
||
615 | <field type="uint8_t" name="autocontinue">autocontinue to next wp</field> |
||
616 | <field type="float" name="param1">PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters</field> |
||
617 | <field type="float" name="param2">PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds</field> |
||
618 | <field type="float" name="param3">PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.</field> |
||
619 | <field type="float" name="param4">PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH</field> |
||
620 | <field type="float" name="x">PARAM5 / local: x position, global: latitude</field> |
||
621 | <field type="float" name="y">PARAM6 / y position: global: longitude</field> |
||
622 | <field type="float" name="z">PARAM7 / z position: global: altitude</field> |
||
623 | </message> |
||
624 | <message id="40" name="WAYPOINT_REQUEST"> |
||
625 | <description>Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message.</description> |
||
626 | <field type="uint8_t" name="target_system">System ID</field> |
||
627 | <field type="uint8_t" name="target_component">Component ID</field> |
||
628 | <field type="uint16_t" name="seq">Sequence</field> |
||
629 | </message> |
||
630 | <message id="41" name="WAYPOINT_SET_CURRENT"> |
||
631 | <description>Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between).</description> |
||
632 | <field type="uint8_t" name="target_system">System ID</field> |
||
633 | <field type="uint8_t" name="target_component">Component ID</field> |
||
634 | <field type="uint16_t" name="seq">Sequence</field> |
||
635 | </message> |
||
636 | <message id="42" name="WAYPOINT_CURRENT"> |
||
637 | <description>Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint.</description> |
||
638 | <field type="uint16_t" name="seq">Sequence</field> |
||
639 | </message> |
||
640 | <message id="43" name="WAYPOINT_REQUEST_LIST"> |
||
641 | <description>Request the overall list of waypoints from the system/component.</description> |
||
642 | <field type="uint8_t" name="target_system">System ID</field> |
||
643 | <field type="uint8_t" name="target_component">Component ID</field> |
||
644 | </message> |
||
645 | <message id="44" name="WAYPOINT_COUNT"> |
||
646 | <description>This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints.</description> |
||
647 | <field type="uint8_t" name="target_system">System ID</field> |
||
648 | <field type="uint8_t" name="target_component">Component ID</field> |
||
649 | <field type="uint16_t" name="count">Number of Waypoints in the Sequence</field> |
||
650 | </message> |
||
651 | <message id="45" name="WAYPOINT_CLEAR_ALL"> |
||
652 | <description>Delete all waypoints at once.</description> |
||
653 | <field type="uint8_t" name="target_system">System ID</field> |
||
654 | <field type="uint8_t" name="target_component">Component ID</field> |
||
655 | </message> |
||
656 | <message id="46" name="WAYPOINT_REACHED"> |
||
657 | <description>A certain waypoint has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint.</description> |
||
658 | <field type="uint16_t" name="seq">Sequence</field> |
||
659 | </message> |
||
660 | <message id="47" name="WAYPOINT_ACK"> |
||
661 | <description>Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).</description> |
||
662 | <field type="uint8_t" name="target_system">System ID</field> |
||
663 | <field type="uint8_t" name="target_component">Component ID</field> |
||
664 | <field type="uint8_t" name="type">0: OK, 1: Error</field> |
||
665 | </message> |
||
666 | <message id="48" name="GPS_SET_GLOBAL_ORIGIN"> |
||
667 | <description>As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description> |
||
668 | <field type="uint8_t" name="target_system">System ID</field> |
||
669 | <field type="uint8_t" name="target_component">Component ID</field> |
||
670 | <field type="int32_t" name="latitude">global position * 1E7</field> |
||
671 | <field type="int32_t" name="longitude">global position * 1E7</field> |
||
672 | <field type="int32_t" name="altitude">global position * 1000</field> |
||
673 | </message> |
||
674 | <message id="49" name="GPS_LOCAL_ORIGIN_SET"> |
||
675 | <description>Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position</description> |
||
676 | <field type="int32_t" name="latitude">Latitude (WGS84), expressed as * 1E7</field> |
||
677 | <field type="int32_t" name="longitude">Longitude (WGS84), expressed as * 1E7</field> |
||
678 | <field type="int32_t" name="altitude">Altitude(WGS84), expressed as * 1000</field> |
||
679 | </message> |
||
680 | <message id="50" name="LOCAL_POSITION_SETPOINT_SET"> |
||
681 | <description>Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/waypoint planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message.</description> |
||
682 | <field type="uint8_t" name="target_system">System ID</field> |
||
683 | <field type="uint8_t" name="target_component">Component ID</field> |
||
684 | <field type="float" name="x">x position</field> |
||
685 | <field type="float" name="y">y position</field> |
||
686 | <field type="float" name="z">z position</field> |
||
687 | <field type="float" name="yaw">Desired yaw angle</field> |
||
688 | </message> |
||
689 | <message id="51" name="LOCAL_POSITION_SETPOINT"> |
||
690 | <description>Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS.</description> |
||
691 | <field type="float" name="x">x position</field> |
||
692 | <field type="float" name="y">y position</field> |
||
693 | <field type="float" name="z">z position</field> |
||
694 | <field type="float" name="yaw">Desired yaw angle</field> |
||
695 | </message> |
||
696 | <message id="52" name="CONTROL_STATUS"> |
||
697 | <field type="uint8_t" name="position_fix">Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix </field> |
||
698 | <field type="uint8_t" name="vision_fix">Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix </field> |
||
699 | <field type="uint8_t" name="gps_fix">GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix </field> |
||
700 | <field type="uint8_t" name="ahrs_health">Attitude estimation health: 0: poor, 255: excellent</field> |
||
701 | <field type="uint8_t" name="control_att">0: Attitude control disabled, 1: enabled</field> |
||
702 | <field type="uint8_t" name="control_pos_xy">0: X, Y position control disabled, 1: enabled</field> |
||
703 | <field type="uint8_t" name="control_pos_z">0: Z position control disabled, 1: enabled</field> |
||
704 | <field type="uint8_t" name="control_pos_yaw">0: Yaw angle control disabled, 1: enabled</field> |
||
705 | </message> |
||
706 | <message id="53" name="SAFETY_SET_ALLOWED_AREA"> |
||
707 | <description>Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations.</description> |
||
708 | <field type="uint8_t" name="target_system">System ID</field> |
||
709 | <field type="uint8_t" name="target_component">Component ID</field> |
||
710 | <field type="uint8_t" name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field> |
||
711 | <field type="float" name="p1x">x position 1 / Latitude 1</field> |
||
712 | <field type="float" name="p1y">y position 1 / Longitude 1</field> |
||
713 | <field type="float" name="p1z">z position 1 / Altitude 1</field> |
||
714 | <field type="float" name="p2x">x position 2 / Latitude 2</field> |
||
715 | <field type="float" name="p2y">y position 2 / Longitude 2</field> |
||
716 | <field type="float" name="p2z">z position 2 / Altitude 2</field> |
||
717 | </message> |
||
718 | <message id="54" name="SAFETY_ALLOWED_AREA"> |
||
719 | <description>Read out the safety zone the MAV currently assumes.</description> |
||
720 | <field type="uint8_t" name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field> |
||
721 | <field type="float" name="p1x">x position 1 / Latitude 1</field> |
||
722 | <field type="float" name="p1y">y position 1 / Longitude 1</field> |
||
723 | <field type="float" name="p1z">z position 1 / Altitude 1</field> |
||
724 | <field type="float" name="p2x">x position 2 / Latitude 2</field> |
||
725 | <field type="float" name="p2y">y position 2 / Longitude 2</field> |
||
726 | <field type="float" name="p2z">z position 2 / Altitude 2</field> |
||
727 | </message> |
||
728 | <message id="55" name="SET_ROLL_PITCH_YAW_THRUST"> |
||
729 | <description>Set roll, pitch and yaw.</description> |
||
730 | <field type="uint8_t" name="target_system">System ID</field> |
||
731 | <field type="uint8_t" name="target_component">Component ID</field> |
||
732 | <field type="float" name="roll">Desired roll angle in radians</field> |
||
733 | <field type="float" name="pitch">Desired pitch angle in radians</field> |
||
734 | <field type="float" name="yaw">Desired yaw angle in radians</field> |
||
735 | <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> |
||
736 | </message> |
||
737 | <message id="56" name="SET_ROLL_PITCH_YAW_SPEED_THRUST"> |
||
738 | <description>Set roll, pitch and yaw.</description> |
||
739 | <field type="uint8_t" name="target_system">System ID</field> |
||
740 | <field type="uint8_t" name="target_component">Component ID</field> |
||
741 | <field type="float" name="roll_speed">Desired roll angular speed in rad/s</field> |
||
742 | <field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field> |
||
743 | <field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field> |
||
744 | <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> |
||
745 | </message> |
||
746 | <message id="57" name="ROLL_PITCH_YAW_THRUST_SETPOINT"> |
||
747 | <description>Setpoint in roll, pitch, yaw currently active on the system.</description> |
||
748 | <field type="uint64_t" name="time_us">Timestamp in micro seconds since unix epoch</field> |
||
749 | <field type="float" name="roll">Desired roll angle in radians</field> |
||
750 | <field type="float" name="pitch">Desired pitch angle in radians</field> |
||
751 | <field type="float" name="yaw">Desired yaw angle in radians</field> |
||
752 | <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> |
||
753 | </message> |
||
754 | <message id="58" name="ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT"> |
||
755 | <description>Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system.</description> |
||
756 | <field type="uint64_t" name="time_us">Timestamp in micro seconds since unix epoch</field> |
||
757 | <field type="float" name="roll_speed">Desired roll angular speed in rad/s</field> |
||
758 | <field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field> |
||
759 | <field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field> |
||
760 | <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> |
||
761 | </message> |
||
762 | <message id="62" name="NAV_CONTROLLER_OUTPUT"> |
||
763 | <description>Outputs of the APM navigation controller. The primary use of this message is to check the response and signs |
||
764 | of the controller before actual flight and to assist with tuning controller parameters </description> |
||
765 | <field type="float" name="nav_roll">Current desired roll in degrees</field> |
||
766 | <field type="float" name="nav_pitch">Current desired pitch in degrees</field> |
||
767 | <field type="int16_t" name="nav_bearing">Current desired heading in degrees</field> |
||
768 | <field type="int16_t" name="target_bearing">Bearing to current waypoint/target in degrees</field> |
||
769 | <field type="uint16_t" name="wp_dist">Distance to active waypoint in meters</field> |
||
770 | <field type="float" name="alt_error">Current altitude error in meters</field> |
||
771 | <field type="float" name="aspd_error">Current airspeed error in meters/second</field> |
||
772 | <field type="float" name="xtrack_error">Current crosstrack error on x-y plane in meters</field> |
||
773 | </message> |
||
774 | <message id="63" name="POSITION_TARGET"> |
||
775 | <description>The goal position of the system. This position is the input to any navigation or path planning algorithm and does NOT represent the current controller setpoint.</description> |
||
776 | <field type="float" name="x">x position</field> |
||
777 | <field type="float" name="y">y position</field> |
||
778 | <field type="float" name="z">z position</field> |
||
779 | <field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field> |
||
780 | </message> |
||
781 | <message id="64" name="STATE_CORRECTION"> |
||
782 | <description>Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle.</description> |
||
783 | <field type="float" name="xErr">x position error</field> |
||
784 | <field type="float" name="yErr">y position error</field> |
||
785 | <field type="float" name="zErr">z position error</field> |
||
786 | <field type="float" name="rollErr">roll error (radians)</field> |
||
787 | <field type="float" name="pitchErr">pitch error (radians)</field> |
||
788 | <field type="float" name="yawErr">yaw error (radians)</field> |
||
789 | <field type="float" name="vxErr">x velocity</field> |
||
790 | <field type="float" name="vyErr">y velocity</field> |
||
791 | <field type="float" name="vzErr">z velocity</field> |
||
792 | </message> |
||
793 | <message id="65" name="SET_ALTITUDE"> |
||
794 | <field type="uint8_t" name="target">The system setting the altitude</field> |
||
795 | <field type="uint32_t" name="mode">The new altitude in meters</field> |
||
796 | </message> |
||
797 | <message id="66" name="REQUEST_DATA_STREAM"> |
||
798 | <field type="uint8_t" name="target_system">The target requested to send the message stream.</field> |
||
799 | <field type="uint8_t" name="target_component">The target requested to send the message stream.</field> |
||
800 | <field type="uint8_t" name="req_stream_id">The ID of the requested message type</field> |
||
801 | <field type="uint16_t" name="req_message_rate">Update rate in Hertz</field> |
||
802 | <field type="uint8_t" name="start_stop">1 to start sending, 0 to stop sending.</field> |
||
803 | </message> |
||
804 | <message id="67" name="HIL_STATE"> |
||
805 | <description>This packet is useful for high throughput |
||
806 | applications such as hardware in the loop simulations. |
||
807 | </description> |
||
808 | <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> |
||
809 | <field type="float" name="roll">Roll angle (rad)</field> |
||
810 | <field type="float" name="pitch">Pitch angle (rad)</field> |
||
811 | <field type="float" name="yaw">Yaw angle (rad)</field> |
||
812 | <field type="float" name="rollspeed">Roll angular speed (rad/s)</field> |
||
813 | <field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field> |
||
814 | <field type="float" name="yawspeed">Yaw angular speed (rad/s)</field> |
||
815 | <field type="int32_t" name="lat">Latitude, expressed as * 1E7</field> |
||
816 | <field type="int32_t" name="lon">Longitude, expressed as * 1E7</field> |
||
817 | <field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters)</field> |
||
818 | <field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field> |
||
819 | <field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field> |
||
820 | <field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field> |
||
821 | <field type="int16_t" name="xacc">X acceleration (mg)</field> |
||
822 | <field type="int16_t" name="yacc">Y acceleration (mg)</field> |
||
823 | <field type="int16_t" name="zacc">Z acceleration (mg)</field> |
||
824 | </message> |
||
825 | <message id="68" name="HIL_CONTROLS"> |
||
826 | <description>Hardware in the loop control outputs</description> |
||
827 | <field type="uint64_t" name="time_us">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> |
||
828 | <field type="float" name="roll_ailerons">Control output -3 .. 1</field> |
||
829 | <field type="float" name="pitch_elevator">Control output -1 .. 1</field> |
||
830 | <field type="float" name="yaw_rudder">Control output -1 .. 1</field> |
||
831 | <field type="float" name="throttle">Throttle 0 .. 1</field> |
||
832 | <field type="uint8_t" name="mode">System mode (MAV_MODE)</field> |
||
833 | <field type="uint8_t" name="nav_mode">Navigation mode (MAV_NAV_MODE)</field> |
||
834 | </message> |
||
835 | <message id="69" name="MANUAL_CONTROL"> |
||
836 | <field type="uint8_t" name="target">The system to be controlled</field> |
||
837 | <field type="float" name="roll">roll</field> |
||
838 | <field type="float" name="pitch">pitch</field> |
||
839 | <field type="float" name="yaw">yaw</field> |
||
840 | <field type="float" name="thrust">thrust</field> |
||
841 | <field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field> |
||
842 | <field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field> |
||
843 | <field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field> |
||
844 | <field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field> |
||
845 | </message> |
||
846 | <message id="70" name="RC_CHANNELS_OVERRIDE"> |
||
847 | <description>The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description> |
||
848 | <field type="uint8_t" name="target_system">System ID</field> |
||
849 | <field type="uint8_t" name="target_component">Component ID</field> |
||
850 | <field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field> |
||
851 | <field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field> |
||
852 | <field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field> |
||
853 | <field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field> |
||
854 | <field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field> |
||
855 | <field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field> |
||
856 | <field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field> |
||
857 | <field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field> |
||
858 | </message> |
||
859 | <message id="73" name="GLOBAL_POSITION_INT"> |
||
860 | <description>The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up)</description> |
||
861 | <field type="int32_t" name="lat">Latitude, expressed as * 1E7</field> |
||
862 | <field type="int32_t" name="lon">Longitude, expressed as * 1E7</field> |
||
863 | <field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters)</field> |
||
864 | <field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field> |
||
865 | <field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field> |
||
866 | <field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field> |
||
867 | </message> |
||
868 | <message id="74" name="VFR_HUD"> |
||
869 | <description>Metrics typically displayed on a HUD for fixed wing aircraft</description> |
||
870 | <field type="float" name="airspeed">Current airspeed in m/s</field> |
||
871 | <field type="float" name="groundspeed">Current ground speed in m/s</field> |
||
872 | <field type="int16_t" name="heading">Current heading in degrees, in compass units (0..360, 0=north)</field> |
||
873 | <field type="uint16_t" name="throttle">Current throttle setting in integer percent, 0 to 100</field> |
||
874 | <field type="float" name="alt">Current altitude (MSL), in meters</field> |
||
875 | <field type="float" name="climb">Current climb rate in meters/second</field> |
||
876 | </message> |
||
877 | <message id="75" name="COMMAND"> |
||
878 | <description>Send a command with up to four parameters to the MAV</description> |
||
879 | <field type="uint8_t" name="target_system">System which should execute the command</field> |
||
880 | <field type="uint8_t" name="target_component">Component which should execute the command, 0 for all components</field> |
||
881 | <field type="uint8_t" name="command">Command ID, as defined by MAV_CMD enum.</field> |
||
882 | <field type="uint8_t" name="confirmation">0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)</field> |
||
883 | <field type="float" name="param1">Parameter 1, as defined by MAV_CMD enum.</field> |
||
884 | <field type="float" name="param2">Parameter 2, as defined by MAV_CMD enum.</field> |
||
885 | <field type="float" name="param3">Parameter 3, as defined by MAV_CMD enum.</field> |
||
886 | <field type="float" name="param4">Parameter 4, as defined by MAV_CMD enum.</field> |
||
887 | </message> |
||
888 | <message id="76" name="COMMAND_ACK"> |
||
889 | <description>Report status of a command. Includes feedback wether the command was executed</description> |
||
890 | <field type="float" name="command">Current airspeed in m/s</field> |
||
891 | <field type="float" name="result">1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION</field> |
||
892 | </message> |
||
893 | <message id="100" name="OPTICAL_FLOW"> |
||
894 | <description>Optical flow from a flow sensor (e.g. optical mouse sensor)</description> |
||
895 | <field type="uint64_t" name="time">Timestamp (UNIX)</field> |
||
896 | <field type="uint8_t" name="sensor_id">Sensor ID</field> |
||
897 | <field type="int16_t" name="flow_x">Flow in pixels in x-sensor direction</field> |
||
898 | <field type="int16_t" name="flow_y">Flow in pixels in y-sensor direction</field> |
||
899 | <field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field> |
||
900 | <field type="float" name="ground_distance">Ground distance in meters</field> |
||
901 | </message> |
||
902 | <message id="140" name="OBJECT_DETECTION_EVENT"> |
||
903 | <description>Object has been detected</description> |
||
904 | <field type="uint32_t" name="time">Timestamp in milliseconds since system boot</field> |
||
905 | <field type="uint16_t" name="object_id">Object ID</field> |
||
906 | <field type="uint8_t" name="type">Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal</field> |
||
907 | <field type="char[20]" name="name">Name of the object as defined by the detector</field> |
||
908 | <field type="uint8_t" name="quality">Detection quality / confidence. 0: bad, 255: maximum confidence</field> |
||
909 | <field type="float" name="bearing">Angle of the object with respect to the body frame in NED coordinates in radians. 0: front</field> |
||
910 | <field type="float" name="distance">Ground distance in meters</field> |
||
911 | </message> |
||
912 | <!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files --> |
||
913 | <message id="251" name="DEBUG_VECT"> |
||
914 | <field type="char[10]" name="name">Name</field> |
||
915 | <field type="uint64_t" name="usec">Timestamp</field> |
||
916 | <field type="float" name="x">x</field> |
||
917 | <field type="float" name="y">y</field> |
||
918 | <field type="float" name="z">z</field> |
||
919 | </message> |
||
920 | <message id="252" name="NAMED_VALUE_FLOAT"> |
||
921 | <description>Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description> |
||
922 | <field type="char[10]" name="name">Name of the debug variable</field> |
||
923 | <field type="float" name="value">Floating point value</field> |
||
924 | </message> |
||
925 | <message id="253" name="NAMED_VALUE_INT"> |
||
926 | <description>Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description> |
||
927 | <field type="char[10]" name="name">Name of the debug variable</field> |
||
928 | <field type="int32_t" name="value">Signed integer value</field> |
||
929 | </message> |
||
930 | <message id="254" name="STATUSTEXT"> |
||
931 | <description>Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).</description> |
||
932 | <field type="uint8_t" name="severity">Severity of status, 0 = info message, 255 = critical fault</field> |
||
933 | <field type="int8_t[50]" name="text">Status text message, without null termination character</field> |
||
934 | </message> |
||
935 | <message id="255" name="DEBUG"> |
||
936 | <description>Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.</description> |
||
937 | <field type="uint8_t" name="ind">index of debug variable</field> |
||
938 | <field type="float" name="value">DEBUG value</field> |
||
939 | </message> |
||
940 | </messages> |
||
941 | </mavlink> |