4#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87
7typedef struct __mavlink_position_target_global_int_t {
21 uint8_t coordinate_frame;
22}) mavlink_position_target_global_int_t;
24#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51
25#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN 51
26#define MAVLINK_MSG_ID_87_LEN 51
27#define MAVLINK_MSG_ID_87_MIN_LEN 51
29#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150
30#define MAVLINK_MSG_ID_87_CRC 150
34#if MAVLINK_COMMAND_24BIT
35#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \
37 "POSITION_TARGET_GLOBAL_INT", \
39 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \
40 { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
41 { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \
42 { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \
43 { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \
44 { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \
45 { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \
46 { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \
47 { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \
48 { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \
49 { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \
50 { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \
51 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \
52 { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \
56#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \
57 "POSITION_TARGET_GLOBAL_INT", \
59 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \
60 { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
61 { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \
62 { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \
63 { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \
64 { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \
65 { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \
66 { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \
67 { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \
68 { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \
69 { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \
70 { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \
71 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \
72 { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \
99static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
100 uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int,
float alt,
float vx,
float vy,
float vz,
float afx,
float afy,
float afz,
float yaw,
float yaw_rate)
102#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
103 char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
104 _mav_put_uint32_t(buf, 0, time_boot_ms);
105 _mav_put_int32_t(buf, 4, lat_int);
106 _mav_put_int32_t(buf, 8, lon_int);
107 _mav_put_float(buf, 12, alt);
108 _mav_put_float(buf, 16, vx);
109 _mav_put_float(buf, 20, vy);
110 _mav_put_float(buf, 24, vz);
111 _mav_put_float(buf, 28, afx);
112 _mav_put_float(buf, 32, afy);
113 _mav_put_float(buf, 36, afz);
114 _mav_put_float(buf, 40, yaw);
115 _mav_put_float(buf, 44, yaw_rate);
116 _mav_put_uint16_t(buf, 48, type_mask);
117 _mav_put_uint8_t(buf, 50, coordinate_frame);
119 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
121 mavlink_position_target_global_int_t packet;
122 packet.time_boot_ms = time_boot_ms;
123 packet.lat_int = lat_int;
124 packet.lon_int = lon_int;
133 packet.yaw_rate = yaw_rate;
134 packet.type_mask = type_mask;
135 packet.coordinate_frame = coordinate_frame;
137 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
140 msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
141 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
166static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
167 mavlink_message_t* msg,
168 uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,
float alt,
float vx,
float vy,
float vz,
float afx,
float afy,
float afz,
float yaw,
float yaw_rate)
170#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
171 char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
172 _mav_put_uint32_t(buf, 0, time_boot_ms);
173 _mav_put_int32_t(buf, 4, lat_int);
174 _mav_put_int32_t(buf, 8, lon_int);
175 _mav_put_float(buf, 12, alt);
176 _mav_put_float(buf, 16, vx);
177 _mav_put_float(buf, 20, vy);
178 _mav_put_float(buf, 24, vz);
179 _mav_put_float(buf, 28, afx);
180 _mav_put_float(buf, 32, afy);
181 _mav_put_float(buf, 36, afz);
182 _mav_put_float(buf, 40, yaw);
183 _mav_put_float(buf, 44, yaw_rate);
184 _mav_put_uint16_t(buf, 48, type_mask);
185 _mav_put_uint8_t(buf, 50, coordinate_frame);
187 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
189 mavlink_position_target_global_int_t packet;
190 packet.time_boot_ms = time_boot_ms;
191 packet.lat_int = lat_int;
192 packet.lon_int = lon_int;
201 packet.yaw_rate = yaw_rate;
202 packet.type_mask = type_mask;
203 packet.coordinate_frame = coordinate_frame;
205 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
208 msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
209 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
220static inline uint16_t mavlink_msg_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_position_target_global_int_t* position_target_global_int)
222 return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate);
234static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_position_target_global_int_t* position_target_global_int)
236 return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate);
258#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
260static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int,
float alt,
float vx,
float vy,
float vz,
float afx,
float afy,
float afz,
float yaw,
float yaw_rate)
262#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
263 char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
264 _mav_put_uint32_t(buf, 0, time_boot_ms);
265 _mav_put_int32_t(buf, 4, lat_int);
266 _mav_put_int32_t(buf, 8, lon_int);
267 _mav_put_float(buf, 12, alt);
268 _mav_put_float(buf, 16, vx);
269 _mav_put_float(buf, 20, vy);
270 _mav_put_float(buf, 24, vz);
271 _mav_put_float(buf, 28, afx);
272 _mav_put_float(buf, 32, afy);
273 _mav_put_float(buf, 36, afz);
274 _mav_put_float(buf, 40, yaw);
275 _mav_put_float(buf, 44, yaw_rate);
276 _mav_put_uint16_t(buf, 48, type_mask);
277 _mav_put_uint8_t(buf, 50, coordinate_frame);
279 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
281 mavlink_position_target_global_int_t packet;
282 packet.time_boot_ms = time_boot_ms;
283 packet.lat_int = lat_int;
284 packet.lon_int = lon_int;
293 packet.yaw_rate = yaw_rate;
294 packet.type_mask = type_mask;
295 packet.coordinate_frame = coordinate_frame;
297 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (
const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
306static inline void mavlink_msg_position_target_global_int_send_struct(mavlink_channel_t chan,
const mavlink_position_target_global_int_t* position_target_global_int)
308#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
309 mavlink_msg_position_target_global_int_send(chan, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate);
311 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (
const char *)position_target_global_int, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
315#if MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
323static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int,
float alt,
float vx,
float vy,
float vz,
float afx,
float afy,
float afz,
float yaw,
float yaw_rate)
325#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
326 char *buf = (
char *)msgbuf;
327 _mav_put_uint32_t(buf, 0, time_boot_ms);
328 _mav_put_int32_t(buf, 4, lat_int);
329 _mav_put_int32_t(buf, 8, lon_int);
330 _mav_put_float(buf, 12, alt);
331 _mav_put_float(buf, 16, vx);
332 _mav_put_float(buf, 20, vy);
333 _mav_put_float(buf, 24, vz);
334 _mav_put_float(buf, 28, afx);
335 _mav_put_float(buf, 32, afy);
336 _mav_put_float(buf, 36, afz);
337 _mav_put_float(buf, 40, yaw);
338 _mav_put_float(buf, 44, yaw_rate);
339 _mav_put_uint16_t(buf, 48, type_mask);
340 _mav_put_uint8_t(buf, 50, coordinate_frame);
342 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
344 mavlink_position_target_global_int_t *packet = (mavlink_position_target_global_int_t *)msgbuf;
345 packet->time_boot_ms = time_boot_ms;
346 packet->lat_int = lat_int;
347 packet->lon_int = lon_int;
356 packet->yaw_rate = yaw_rate;
357 packet->type_mask = type_mask;
358 packet->coordinate_frame = coordinate_frame;
360 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (
const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
375static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(
const mavlink_message_t* msg)
377 return _MAV_RETURN_uint32_t(msg, 0);
385static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(
const mavlink_message_t* msg)
387 return _MAV_RETURN_uint8_t(msg, 50);
395static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(
const mavlink_message_t* msg)
397 return _MAV_RETURN_uint16_t(msg, 48);
405static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(
const mavlink_message_t* msg)
407 return _MAV_RETURN_int32_t(msg, 4);
415static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(
const mavlink_message_t* msg)
417 return _MAV_RETURN_int32_t(msg, 8);
425static inline float mavlink_msg_position_target_global_int_get_alt(
const mavlink_message_t* msg)
427 return _MAV_RETURN_float(msg, 12);
435static inline float mavlink_msg_position_target_global_int_get_vx(
const mavlink_message_t* msg)
437 return _MAV_RETURN_float(msg, 16);
445static inline float mavlink_msg_position_target_global_int_get_vy(
const mavlink_message_t* msg)
447 return _MAV_RETURN_float(msg, 20);
455static inline float mavlink_msg_position_target_global_int_get_vz(
const mavlink_message_t* msg)
457 return _MAV_RETURN_float(msg, 24);
465static inline float mavlink_msg_position_target_global_int_get_afx(
const mavlink_message_t* msg)
467 return _MAV_RETURN_float(msg, 28);
475static inline float mavlink_msg_position_target_global_int_get_afy(
const mavlink_message_t* msg)
477 return _MAV_RETURN_float(msg, 32);
485static inline float mavlink_msg_position_target_global_int_get_afz(
const mavlink_message_t* msg)
487 return _MAV_RETURN_float(msg, 36);
495static inline float mavlink_msg_position_target_global_int_get_yaw(
const mavlink_message_t* msg)
497 return _MAV_RETURN_float(msg, 40);
505static inline float mavlink_msg_position_target_global_int_get_yaw_rate(
const mavlink_message_t* msg)
507 return _MAV_RETURN_float(msg, 44);
516static inline void mavlink_msg_position_target_global_int_decode(
const mavlink_message_t* msg, mavlink_position_target_global_int_t* position_target_global_int)
518#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
519 position_target_global_int->time_boot_ms = mavlink_msg_position_target_global_int_get_time_boot_ms(msg);
520 position_target_global_int->lat_int = mavlink_msg_position_target_global_int_get_lat_int(msg);
521 position_target_global_int->lon_int = mavlink_msg_position_target_global_int_get_lon_int(msg);
522 position_target_global_int->alt = mavlink_msg_position_target_global_int_get_alt(msg);
523 position_target_global_int->vx = mavlink_msg_position_target_global_int_get_vx(msg);
524 position_target_global_int->vy = mavlink_msg_position_target_global_int_get_vy(msg);
525 position_target_global_int->vz = mavlink_msg_position_target_global_int_get_vz(msg);
526 position_target_global_int->afx = mavlink_msg_position_target_global_int_get_afx(msg);
527 position_target_global_int->afy = mavlink_msg_position_target_global_int_get_afy(msg);
528 position_target_global_int->afz = mavlink_msg_position_target_global_int_get_afz(msg);
529 position_target_global_int->yaw = mavlink_msg_position_target_global_int_get_yaw(msg);
530 position_target_global_int->yaw_rate = mavlink_msg_position_target_global_int_get_yaw_rate(msg);
531 position_target_global_int->type_mask = mavlink_msg_position_target_global_int_get_type_mask(msg);
532 position_target_global_int->coordinate_frame = mavlink_msg_position_target_global_int_get_coordinate_frame(msg);
534 uint8_t len = msg->len < MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN? msg->len : MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN;
535 memset(position_target_global_int, 0, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
536 memcpy(position_target_global_int, _MAV_PAYLOAD(msg), len);