Robot Control Library
mavlink_udp_helpers.h
Go to the documentation of this file.
1/**
2 * <rc/mavlink_udp_helpers.h>
3 *
4 * @brief helper functions for the most common mavlink packets.
5 *
6 * For use with the functions in mavlink_udp.h
7 *
8 * @author James Strawson & Henry Gaudet
9 * @date 1/24/2018
10 *
11 * @addtogroup Mavlink_Helpers
12 * @ingroup Mavlink
13 * @{
14 */
15
16#ifndef RC_MAVLINK_UDP_HELPERS_H
17#define RC_MAVLINK_UDP_HELPERS_H
18
19#ifdef __cplusplus
20extern "C" {
21#endif
22
23
24#include <stdint.h> // for specific integer types
25
26// these are directly from the mavlink source
27#include <rc/mavlink/common/mavlink.h>
28#include <rc/mavlink/mavlink_types.h>
29
30
31
32/**
33 * @brief Constructs and sends a heartbeat packet of type
34 * MAVLINK_MSG_ID_HEARTBEAT
35 *
36 * This is a shortcut for rc_mav_send_heartbeat for those which don't wish to
37 * populate all of the availbale fields in the mavlink heartbeat packet. It
38 * still sends a complete heartbeat packet but with all 0's in the packet
39 * payload fields. The receiver can still see the system_id of the sender and
40 * this still serves the primary purpose to the heartbeat packet which is to
41 * indicate that a communication channel is open and functioning.
42 *
43 * @return 0 on success or -1 on failure.
44 */
46
47/**
48 * @brief Constructs and sends a heartbeat packet of type
49 * MAVLINK_MSG_ID_HEARTBEAT
50 *
51 * Constructs and sends a heartbeat packet to the previously set destination ip
52 * address. The arguments encompass all available parameters in the heartbeat
53 * packet. However, many users will not be bothered to populate these parameters
54 * and may opt to use rc_mav_send_heartbeat_abbreviated() instead.
55 *
56 * @param[in] custom_mode A bitfield for use for autopilot-specific flags.
57 * @param[in] type Type of the MAV (quadrotor, helicopter, etc., up
58 * to 15 types, defined in MAV_TYPE ENUM)
59 * @param[in] autopilot Autopilot type / class. defined in MAV_AUTOPILOT
60 * ENUM
61 * @param[in] base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in
62 * mavlink/include/mavlink_types.h
63 * @param[in] system_status System status flag, see MAV_STATE ENUM
64 *
65 * @return 0 on success, -1 on failure
66 */
68 uint32_t custom_mode,
69 uint8_t type,
70 uint8_t autopilot,
71 uint8_t base_mode,
72 uint8_t system_status);
73
74
75/**
76 * @brief fetches the most recently received heartbeat packet of type
77 * MAVLINK_MSG_ID_HEARTBEAT
78 *
79 * @param[out] data pointer to put heartbeat packet data
80 *
81 * @return 0 on success, -1 on failure for example if no message has been
82 * received of type msg_id.
83 */
84int rc_mav_get_heartbeat(mavlink_heartbeat_t* data);
85
86
87/**
88 * @brief Send and attitude packet of type MAVLINK_MSG_ID_ATTITUDE
89 *
90 * @param[in] roll Roll angle (rad, -pi..+pi)
91 * @param[in] pitch Pitch angle (rad, -pi..+pi)
92 * @param[in] yaw Yaw angle (rad, -pi..+pi)
93 * @param[in] rollspeed Roll angular speed (rad/s)
94 * @param[in] pitchspeed Pitch angular speed (rad/s)
95 * @param[in] yawspeed Yaw angular speed (rad/s)
96 *
97 * @return 0 on success, -1 on failure
98 */
100 float roll,
101 float pitch,
102 float yaw,
103 float rollspeed,
104 float pitchspeed,
105 float yawspeed);
106
107/**
108 * @brief Fetches the last attitude packet of type MAVLINK_MSG_ID_ATTITUDE
109 *
110 * @param[out] data Pointer to user's packet struct to be populated with new
111 * data
112 *
113 * @return 0 on success, -1 on failure
114 */
115int rc_mav_get_attitude(mavlink_attitude_t* data);
116
117
118/**
119 * @brief Packs and sends an attitude quaternion packet of type
120 * MAVLINK_MSG_ID_ATTITUDE_QUATERNION
121 *
122 * @param[in] q1 Quaternion component 1
123 * @param[in] q2 Quaternion component 2
124 * @param[in] q3 Quaternion component 3
125 * @param[in] q4 Quaternion component 4
126 * @param[in] rollspeed Roll angular speed (rad/s)
127 * @param[in] pitchspeed Pitch angular speed (rad/s)
128 * @param[in] yawspeed Yaw angular speed (rad/s)
129 *
130 * @return 0 on success, -1 on failure
131 */
133 float q1,
134 float q2,
135 float q3,
136 float q4,
137 float rollspeed,
138 float pitchspeed,
139 float yawspeed);
140
141
142/**
143 * @brief Fetches and unpacks the last received
144 * MAVLINK_MSG_ID_ATTITUDE_QUATERNION
145 *
146 * @param[out] data Pointer to user's packet struct to be populated with new
147 * data
148 *
149 * @return 0 on success, -1 on failure
150 */
151int rc_mav_get_attitude_quaternion(mavlink_attitude_quaternion_t* data);
152
153
154/**
155 * @brief Packs and sends a local position NED packet of type
156 * MAVLINK_MSG_ID_LOCAL_POSITION_NED
157 *
158 * @param[in] x X Position (meters)
159 * @param[in] y Y Position (meters)
160 * @param[in] z Z Position (meters)
161 * @param[in] vx X Speed (m/s)
162 * @param[in] vy Y Speed (m/s)
163 * @param[in] vz Z Speed (m/s)
164 *
165 * @return 0 on success, -1 on failure
166 */
168 float x,
169 float y,
170 float z,
171 float vx,
172 float vy,
173 float vz);
174
175
176/**
177 * @brief Fetches and unpacks the last received
178 * MAVLINK_MSG_ID_LOCAL_POSITION_NED
179 *
180 * @param[out] data Pointer to user's packet struct to be populated with new
181 * data
182 *
183 * @return 0 on success, -1 on failure
184 */
185int rc_mav_get_local_position_ned(mavlink_local_position_ned_t* data);
186
187
188/**
189 * @brief Packs and sends a packet of type
190 * MAVLINK_MSG_ID_GLOBAL_POSITION_INT
191 *
192 * @param[in] lat Latitude, expressed as * 1E7
193 * @param[in] lon Longitude, expressed as * 1E7
194 * @param[in] alt Altitude in meters, expressed as * 1000
195 * (millimeters), above MSL
196 * @param[in] relative_alt Altitude above ground in meters, expressed as *
197 * 1000 (millimeters)
198 * @param[in] vx Ground X Speed (Latitude), expressed as m/s * 100
199 * @param[in] vy Ground Y Speed (Longitude), expressed as m/s * 100
200 * @param[in] vz Ground Z Speed (Altitude), expressed as m/s * 100
201 * @param[in] hdg Compass heading in degrees * 100, 0.0..359.99
202 * degrees. If unknown, set to: UINT16_MAX
203 *
204 * @return 0 on success, -1 on failure
205 */
207 int32_t lat,
208 int32_t lon,
209 int32_t alt,
210 int32_t relative_alt,
211 int16_t vx,
212 int16_t vy,
213 int16_t vz,
214 uint16_t hdg);
215
216
217/**
218 * @brief Fetches and unpacks the last received
219 * MAVLINK_MSG_ID_GLOBAL_POSITION_INT
220 *
221 * @param[out] data Pointer to user's packet struct to be populated with new
222 * data
223 *
224 * @return 0 on success, -1 on failure
225 */
226int rc_mav_get_global_position_int(mavlink_global_position_int_t* data);
227
228
229/**
230 * @brief Packs and sends a packet of type
231 * MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED
232 *
233 * @param[in] x X Position in NED frame in m
234 * @param[in] y Y Position in NED frame in m
235 * @param[in] z Z Position in NED frame in meters (note,
236 * altitude is negative in NED)
237 * @param[in] vx X velocity in NED frame in m/s
238 * @param[in] vy Y velocity in NED frame in m/s
239 * @param[in] vz Z velocity in NED frame in m/s
240 * @param[in] afx X acceleration or force (if bit 10 of type_mask
241 * is set) in NED frame in meter/s^2 or N
242 * @param[in] afy Y acceleration or force (if bit 10 of type_mask
243 * is set) in NED frame in meter/s^2 or N
244 * @param[in] afz Z acceleration or force (if bit 10 of type_mask
245 * is set) in NED frame in meter/s^2 or N
246 * @param[in] yaw yaw setpoint in rad
247 * @param[in] yaw_rate yaw rate setpoint in rad/s
248 * @param[in] type_mask Bitmask to indicate which dimensions should be
249 * ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000
250 * indicates that none of the setpoint dimensions should be ignored. If bit 10
251 * is set the floats afx afy afz should be interpreted as force instead of
252 * acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy,
253 * bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit
254 * 11: yaw, bit 12: yaw rate
255 * @param[in] target_system System ID of the target system
256 * @param[in] target_component Component ID
257 * @param[in] coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1,
258 * MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8,
259 * MAV_FRAME_BODY_OFFSET_NED = 9
260 *
261 * @return 0 on success, -1 on failure
262 */
264 float x,
265 float y,
266 float z,
267 float vx,
268 float vy,
269 float vz,
270 float afx,
271 float afy,
272 float afz,
273 float yaw,
274 float yaw_rate,
275 uint16_t type_mask,
276 uint8_t target_system,
277 uint8_t target_component,
278 uint8_t coordinate_frame);
279
280
281/**
282 * @brief fetches and unpacks the most recently received packet of type
283 * MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED
284 *
285 * @param[out] data Pointer to user's packet struct to be populated with new
286 * data
287 *
288 * @return 0 on success, -1 on failure
289 */
290int rc_mav_get_set_position_target_local_ned(mavlink_set_position_target_local_ned_t* data);
291
292
293/**
294 * @brief Packs and sends a packet of type
295 * MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT
296 *
297 * @param[in] lat_int X Position in WGS84 frame in 1e7 * degrees
298 * @param[in] lon_int Y Position in WGS84 frame in 1e7 * degrees
299 * @param[in] alt Altitude in meters in AMSL altitude, not WGS84
300 * if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
301 * @param[in] vx X velocity in NED frame in m/s
302 * @param[in] vy Y velocity in NED frame in m/s
303 * @param[in] vz Z velocity in NED frame in m/s
304 * @param[in] afx X acceleration or force (if bit 10 of type_mask
305 * is set) in NED frame in meter/s^2 or N
306 * @param[in] afy Y acceleration or force (if bit 10 of type_mask
307 * is set) in NED frame in meter/s^2 or N
308 * @param[in] afz Z acceleration or force (if bit 10 of type_mask
309 * is set) in NED frame in meter/s^2 or N
310 * @param[in] yaw yaw setpoint in rad
311 * @param[in] yaw_rate yaw rate setpoint in rad/s
312 * @param[in] type_mask Bitmask to indicate which dimensions should be
313 * ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000
314 * indicates that none of the setpoint dimensions should be ignored. If bit 10
315 * is set the floats afx afy afz should be interpreted as force instead of
316 * acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy,
317 * bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit
318 * 11: yaw, bit 12: yaw rate
319 * @param[in] target_system System ID
320 * @param[in] target_component Component ID
321 * @param[in] coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5,
322 * MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
323 *
324 * @return 0 on success, -1 on failure
325 */
327 int32_t lat_int,
328 int32_t lon_int,
329 float alt,
330 float vx,
331 float vy,
332 float vz,
333 float afx,
334 float afy,
335 float afz,
336 float yaw,
337 float yaw_rate,
338 uint16_t type_mask,
339 uint8_t target_system,
340 uint8_t target_component,
341 uint8_t coordinate_frame);
342
343
344/**
345 * @brief Fetches and unpacks the last received packet of type
346 * MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT
347 *
348 * @param[out] data Pointer to user's packet struct to be populated with new
349 * data
350 *
351 * @return 0 on success, -1 on failure
352 */
353int rc_mav_get_set_position_target_global_int(mavlink_set_position_target_global_int_t* data);
354
355
356/**
357 * @brief Packs and sends a packet of type MAVLINK_MSG_ID_GPS_RAW_INT
358 *
359 * @param[in] lat Latitude (WGS84, EGM96 ellipsoid), in degrees *
360 * 1E7
361 * @param[in] lon Longitude (WGS84, EGM96 ellipsoid), in
362 * degrees * 1E7
363 * @param[in] alt Altitude (AMSL, NOT WGS84), in meters * 1000
364 * (positive for up). Note that virtually all GPS modules provide the AMSL
365 * altitude in addition to the WGS84 altitude.
366 * @param[in] eph GPS HDOP horizontal dilution of position
367 * (unitless). If unknown, set to: UINT16_MAX
368 * @param[in] epv GPS VDOP vertical dilution of position
369 * (unitless). If unknown, set to: UINT16_MAX
370 * @param[in] vel GPS ground speed (m/s * 100). If unknown, set
371 * to: UINT16_MAX
372 * @param[in] cog Course over ground (NOT heading, but
373 * direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set
374 * to: UINT16_MAX
375 * @param[in] fix_type See the GPS_FIX_TYPE enum.
376 * @param[in] satellites_visible Number of satellites visible. If unknown, set
377 * to 255
378 * @param[in] alt_ellipsoid Altitude (above WGS84, EGM96 ellipsoid), in
379 * meters * 1000 (positive for up).
380 * @param[in] h_acc Position uncertainty in meters * 1000
381 * (positive for up).
382 * @param[in] v_acc Altitude uncertainty in meters * 1000
383 * (positive for up).
384 * @param[in] vel_acc Speed uncertainty in meters * 1000 (positive
385 * for up).
386 * @param[in] hdg_acc Heading / track uncertainty in degrees * 1e5.
387 *
388 * @return 0 on success, -1 on failure
389 */
391 int32_t lat,
392 int32_t lon,
393 int32_t alt,
394 uint16_t eph,
395 uint16_t epv,
396 uint16_t vel,
397 uint16_t cog,
398 uint8_t fix_type,
399 uint8_t satellites_visible,
400 int32_t alt_ellipsoid,
401 uint32_t h_acc,
402 uint32_t v_acc,
403 uint32_t vel_acc,
404 uint32_t hdg_acc);
405
406
407/**
408 * @brief Fetches and unpacks a packet of type MAVLINK_MSG_ID_GPS_RAW_INT
409 *
410 * @param[out] data Pointer to user's packet struct to be populated with new
411 * data
412 *
413 * @return 0 on success, -1 on failure
414 */
415int rc_mav_get_gps_raw_int(mavlink_gps_raw_int_t* data);
416
417
418/**
419 * @brief Packs and sends a packet of type MAVLINK_MSG_ID_SCALED_PRESSURE
420 *
421 * @param[in] press_abs Absolute pressure (hectopascal)
422 * @param[in] press_diff Differential pressure 1 (hectopascal)
423 * @param[in] temperature Temperature measurement (0.01 degrees celsius)
424 *
425 * @return 0 on success, -1 on failure
426 */
428 float press_abs,
429 float press_diff,
430 int16_t temperature);
431
432/**
433 * @brief Fetches and unpacks last received packet of type
434 * MAVLINK_MSG_ID_SCALED_PRESSURE
435 *
436 * @param[out] data Pointer to user's packet struct to be populated with new
437 * data
438 *
439 * @return 0 on success, -1 on failure
440 */
441int rc_mav_get_scaled_pressure(mavlink_scaled_pressure_t* data);
442
443
444/**
445 * @brief Packs and sends packet of type MAVLINK_MSG_ID_SERVO_OUTPUT_RAW
446 *
447 * @param[in] servo1_raw Servo output 1 value, in microseconds
448 * @param[in] servo2_raw Servo output 2 value, in microseconds
449 * @param[in] servo3_raw Servo output 3 value, in microseconds
450 * @param[in] servo4_raw Servo output 4 value, in microseconds
451 * @param[in] servo5_raw Servo output 5 value, in microseconds
452 * @param[in] servo6_raw Servo output 6 value, in microseconds
453 * @param[in] servo7_raw Servo output 7 value, in microseconds
454 * @param[in] servo8_raw Servo output 8 value, in microseconds
455 * @param[in] port Servo output port (set of 8 outputs = 1 port). Most
456 * MAVs will just use one, but this allows to encode more than 8 servos.
457 * @param[in] servo9_raw Servo output 9 value, in microseconds
458 * @param[in] servo10_raw Servo output 10 value, in microseconds
459 * @param[in] servo11_raw Servo output 11 value, in microseconds
460 * @param[in] servo12_raw Servo output 12 value, in microseconds
461 * @param[in] servo13_raw Servo output 13 value, in microseconds
462 * @param[in] servo14_raw Servo output 14 value, in microseconds
463 * @param[in] servo15_raw Servo output 15 value, in microseconds
464 * @param[in] servo16_raw Servo output 16 value, in microseconds
465 *
466 * @return 0 on success, -1 on failure
467 */
469 uint16_t servo1_raw,
470 uint16_t servo2_raw,
471 uint16_t servo3_raw,
472 uint16_t servo4_raw,
473 uint16_t servo5_raw,
474 uint16_t servo6_raw,
475 uint16_t servo7_raw,
476 uint16_t servo8_raw,
477 uint8_t port,
478 uint16_t servo9_raw,
479 uint16_t servo10_raw,
480 uint16_t servo11_raw,
481 uint16_t servo12_raw,
482 uint16_t servo13_raw,
483 uint16_t servo14_raw,
484 uint16_t servo15_raw,
485 uint16_t servo16_raw);
486
487
488/**
489 * @brief Fetch and unpack message of type MAVLINK_MSG_ID_SERVO_OUTPUT_RAW
490 *
491 * @param[out] data Pointer to user's packet struct to be populated with new
492 * data
493 *
494 * @return 0 on success, -1 on failure
495 */
496int rc_mav_get_servo_output_raw(mavlink_servo_output_raw_t* data);
497
498
499/**
500 * @brief { function_description }
501 *
502 * @param[in] onboard_control_sensors_present Bitmask showing which onboard
503 * controllers and sensors are present. Value of 0: not present. Value of 1:
504 * present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
505 * @param[in] onboard_control_sensors_enabled Bitmask showing which onboard
506 * controllers and sensors are enabled: Value of 0: not enabled. Value of 1:
507 * enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
508 * @param[in] onboard_control_sensors_health Bitmask showing which onboard
509 * controllers and sensors are operational or have an error: Value of 0: not
510 * enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
511 * @param[in] load Maximum usage in percent of the
512 * mainloop time, (0%: 0, 100%: 1000) should be always below 1000
513 * @param[in] voltage_battery Battery voltage, in millivolts
514 * (1 = 1 millivolt)
515 * @param[in] current_battery Battery current, in
516 * 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the
517 * current
518 * @param[in] drop_rate_comm Communication drops in percent,
519 * (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links
520 * (packets that were corrupted on reception on the MAV)
521 * @param[in] errors_comm Communication errors (UART, I2C,
522 * SPI, CAN), dropped packets on all links (packets that were corrupted on
523 * reception on the MAV)
524 * @param[in] errors_count1 Autopilot-specific errors
525 * @param[in] errors_count2 Autopilot-specific errors
526 * @param[in] errors_count3 Autopilot-specific errors
527 * @param[in] errors_count4 Autopilot-specific errors
528 * @param[in] battery_remaining Remaining battery energy: (0%:
529 * 0, 100%: 100), -1: autopilot estimate the remaining battery
530 *
531 * @return 0 on success, -1 on failure
532 */
534 uint32_t onboard_control_sensors_present,
535 uint32_t onboard_control_sensors_enabled,
536 uint32_t onboard_control_sensors_health,
537 uint16_t load,
538 uint16_t voltage_battery,
539 int16_t current_battery,
540 uint16_t drop_rate_comm,
541 uint16_t errors_comm,
542 uint16_t errors_count1,
543 uint16_t errors_count2,
544 uint16_t errors_count3,
545 uint16_t errors_count4,
546 int8_t battery_remaining);
547
548
549/**
550 * @brief Fetch and unpack packet of type MAVLINK_MSG_ID_SERVO_OUTPUT_RAW
551 *
552 * @param[out] data Pointer to user's packet struct to be populated with new
553 * data
554 *
555 * @return 0 on success, -1 on failure
556 */
557int rc_mav_get_sys_status(mavlink_sys_status_t* data);
558
559
560/**
561 * @brief Pack and send message of type MAVLINK_MSG_ID_MANUAL_CONTROL
562 *
563 * @param[in] x X-axis, normalized to the range [-1000,1000]. A value of
564 * INT16_MAX indicates that this axis is invalid. Generally corresponds to
565 * forward(1000)-backward(-1000) movement on a joystick and the pitch of a
566 * vehicle.
567 * @param[in] y Y-axis, normalized to the range [-1000,1000]. A value of
568 * INT16_MAX indicates that this axis is invalid. Generally corresponds to
569 * left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
570 * @param[in] z Z-axis, normalized to the range [-1000,1000]. A value of
571 * INT16_MAX indicates that this axis is invalid. Generally corresponds to a
572 * separate slider movement with maximum being 1000 and minimum being -1000 on a
573 * joystick and the thrust of a vehicle.
574 * @param[in] r R-axis, normalized to the range [-1000,1000]. A value of
575 * INT16_MAX indicates that this axis is invalid. Generally corresponds to a
576 * twisting of the joystick, with counter-clockwise being 1000 and clockwise
577 * being -1000, and the yaw of a vehicle.
578 * @param[in] buttons A bitfield corresponding to the joystick buttons'
579 * current state, 1 for pressed, 0 for released. The lowest bit corresponds to
580 * Button 1.
581 * @param[in] target The system to be controlled.
582 *
583 * @return 0 on success, -1 on failure
584 */
586 int16_t x,
587 int16_t y,
588 int16_t z,
589 int16_t r,
590 uint16_t buttons,
591 uint8_t target);
592
593
594/**
595 * @brief Fetch and unpack the last received message of type
596 * MAVLINK_MSG_ID_MANUAL_CONTROL
597 *
598 * @param[out] data Pointer to user's packet struct to be populated with new
599 * data
600 *
601 * @return 0 on success, -1 on failure
602 */
603int rc_mav_get_manual_control(mavlink_manual_control_t* data);
604
605
606/**
607 * @brief Packs and send a message of type MAVLINK_MSG_ID_ATT_POS_MOCAP
608 *
609 * @param q Attitude quaternion, w, x, y, z order, zero-rotation is
610 * (1,0,0,0)
611 * @param[in] x X position in meters (NED)
612 * @param[in] y Y position in meters (NED)
613 * @param[in] z Z position in meters (NED)
614 *
615 * @return 0 on success, -1 on failure
616 */
618 float q[4],
619 float x,
620 float y,
621 float z);
622
623
624/**
625 * @brief Fetche and unpacks last received packet of type
626 * MAVLINK_MSG_ID_ATT_POS_MOCAP
627 *
628 * @param[out] data Pointer to user's packet struct to be populated with new
629 * data
630 *
631 * @return 0 on success, -1 on failure
632 */
633int rc_mav_get_att_pos_mocap(mavlink_att_pos_mocap_t* data);
634
635
636#ifdef __cplusplus
637}
638#endif
639
640#endif // RC_MAVLINK_UDP_HELPERS_H
641
642///@} end group Mavlink_Helpers