4#define MAVLINK_MSG_ID_MISSION_ITEM_INT 73
7typedef struct __mavlink_mission_item_int_t {
17 uint8_t target_system;
18 uint8_t target_component;
23}) mavlink_mission_item_int_t;
25#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 38
26#define MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN 37
27#define MAVLINK_MSG_ID_73_LEN 38
28#define MAVLINK_MSG_ID_73_MIN_LEN 37
30#define MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC 38
31#define MAVLINK_MSG_ID_73_CRC 38
35#if MAVLINK_COMMAND_24BIT
36#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \
40 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \
41 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \
42 { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
43 { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \
44 { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \
45 { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \
46 { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \
47 { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \
48 { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \
49 { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \
50 { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \
51 { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \
52 { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \
53 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \
54 { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_int_t, mission_type) }, \
58#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \
61 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \
62 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \
63 { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
64 { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \
65 { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \
66 { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \
67 { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \
68 { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \
69 { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \
70 { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \
71 { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \
72 { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \
73 { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \
74 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \
75 { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_int_t, mission_type) }, \
103static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
104 uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue,
float param1,
float param2,
float param3,
float param4, int32_t x, int32_t y,
float z, uint8_t mission_type)
106#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107 char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
108 _mav_put_float(buf, 0, param1);
109 _mav_put_float(buf, 4, param2);
110 _mav_put_float(buf, 8, param3);
111 _mav_put_float(buf, 12, param4);
112 _mav_put_int32_t(buf, 16, x);
113 _mav_put_int32_t(buf, 20, y);
114 _mav_put_float(buf, 24, z);
115 _mav_put_uint16_t(buf, 28, seq);
116 _mav_put_uint16_t(buf, 30, command);
117 _mav_put_uint8_t(buf, 32, target_system);
118 _mav_put_uint8_t(buf, 33, target_component);
119 _mav_put_uint8_t(buf, 34, frame);
120 _mav_put_uint8_t(buf, 35, current);
121 _mav_put_uint8_t(buf, 36, autocontinue);
122 _mav_put_uint8_t(buf, 37, mission_type);
124 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
126 mavlink_mission_item_int_t packet;
127 packet.param1 = param1;
128 packet.param2 = param2;
129 packet.param3 = param3;
130 packet.param4 = param4;
135 packet.command = command;
136 packet.target_system = target_system;
137 packet.target_component = target_component;
138 packet.frame = frame;
139 packet.current = current;
140 packet.autocontinue = autocontinue;
141 packet.mission_type = mission_type;
143 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
146 msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT;
147 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
173static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
174 mavlink_message_t* msg,
175 uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,
float param1,
float param2,
float param3,
float param4,int32_t x,int32_t y,
float z,uint8_t mission_type)
177#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
178 char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
179 _mav_put_float(buf, 0, param1);
180 _mav_put_float(buf, 4, param2);
181 _mav_put_float(buf, 8, param3);
182 _mav_put_float(buf, 12, param4);
183 _mav_put_int32_t(buf, 16, x);
184 _mav_put_int32_t(buf, 20, y);
185 _mav_put_float(buf, 24, z);
186 _mav_put_uint16_t(buf, 28, seq);
187 _mav_put_uint16_t(buf, 30, command);
188 _mav_put_uint8_t(buf, 32, target_system);
189 _mav_put_uint8_t(buf, 33, target_component);
190 _mav_put_uint8_t(buf, 34, frame);
191 _mav_put_uint8_t(buf, 35, current);
192 _mav_put_uint8_t(buf, 36, autocontinue);
193 _mav_put_uint8_t(buf, 37, mission_type);
195 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
197 mavlink_mission_item_int_t packet;
198 packet.param1 = param1;
199 packet.param2 = param2;
200 packet.param3 = param3;
201 packet.param4 = param4;
206 packet.command = command;
207 packet.target_system = target_system;
208 packet.target_component = target_component;
209 packet.frame = frame;
210 packet.current = current;
211 packet.autocontinue = autocontinue;
212 packet.mission_type = mission_type;
214 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
217 msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT;
218 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
229static inline uint16_t mavlink_msg_mission_item_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_mission_item_int_t* mission_item_int)
231 return mavlink_msg_mission_item_int_pack(system_id, component_id, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z, mission_item_int->mission_type);
243static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_mission_item_int_t* mission_item_int)
245 return mavlink_msg_mission_item_int_pack_chan(system_id, component_id, chan, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z, mission_item_int->mission_type);
268#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
270static inline void mavlink_msg_mission_item_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue,
float param1,
float param2,
float param3,
float param4, int32_t x, int32_t y,
float z, uint8_t mission_type)
272#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
273 char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
274 _mav_put_float(buf, 0, param1);
275 _mav_put_float(buf, 4, param2);
276 _mav_put_float(buf, 8, param3);
277 _mav_put_float(buf, 12, param4);
278 _mav_put_int32_t(buf, 16, x);
279 _mav_put_int32_t(buf, 20, y);
280 _mav_put_float(buf, 24, z);
281 _mav_put_uint16_t(buf, 28, seq);
282 _mav_put_uint16_t(buf, 30, command);
283 _mav_put_uint8_t(buf, 32, target_system);
284 _mav_put_uint8_t(buf, 33, target_component);
285 _mav_put_uint8_t(buf, 34, frame);
286 _mav_put_uint8_t(buf, 35, current);
287 _mav_put_uint8_t(buf, 36, autocontinue);
288 _mav_put_uint8_t(buf, 37, mission_type);
290 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
292 mavlink_mission_item_int_t packet;
293 packet.param1 = param1;
294 packet.param2 = param2;
295 packet.param3 = param3;
296 packet.param4 = param4;
301 packet.command = command;
302 packet.target_system = target_system;
303 packet.target_component = target_component;
304 packet.frame = frame;
305 packet.current = current;
306 packet.autocontinue = autocontinue;
307 packet.mission_type = mission_type;
309 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (
const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
318static inline void mavlink_msg_mission_item_int_send_struct(mavlink_channel_t chan,
const mavlink_mission_item_int_t* mission_item_int)
320#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
321 mavlink_msg_mission_item_int_send(chan, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z, mission_item_int->mission_type);
323 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (
const char *)mission_item_int, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
327#if MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
335static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue,
float param1,
float param2,
float param3,
float param4, int32_t x, int32_t y,
float z, uint8_t mission_type)
337#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
338 char *buf = (
char *)msgbuf;
339 _mav_put_float(buf, 0, param1);
340 _mav_put_float(buf, 4, param2);
341 _mav_put_float(buf, 8, param3);
342 _mav_put_float(buf, 12, param4);
343 _mav_put_int32_t(buf, 16, x);
344 _mav_put_int32_t(buf, 20, y);
345 _mav_put_float(buf, 24, z);
346 _mav_put_uint16_t(buf, 28, seq);
347 _mav_put_uint16_t(buf, 30, command);
348 _mav_put_uint8_t(buf, 32, target_system);
349 _mav_put_uint8_t(buf, 33, target_component);
350 _mav_put_uint8_t(buf, 34, frame);
351 _mav_put_uint8_t(buf, 35, current);
352 _mav_put_uint8_t(buf, 36, autocontinue);
353 _mav_put_uint8_t(buf, 37, mission_type);
355 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
357 mavlink_mission_item_int_t *packet = (mavlink_mission_item_int_t *)msgbuf;
358 packet->param1 = param1;
359 packet->param2 = param2;
360 packet->param3 = param3;
361 packet->param4 = param4;
366 packet->command = command;
367 packet->target_system = target_system;
368 packet->target_component = target_component;
369 packet->frame = frame;
370 packet->current = current;
371 packet->autocontinue = autocontinue;
372 packet->mission_type = mission_type;
374 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (
const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
389static inline uint8_t mavlink_msg_mission_item_int_get_target_system(
const mavlink_message_t* msg)
391 return _MAV_RETURN_uint8_t(msg, 32);
399static inline uint8_t mavlink_msg_mission_item_int_get_target_component(
const mavlink_message_t* msg)
401 return _MAV_RETURN_uint8_t(msg, 33);
409static inline uint16_t mavlink_msg_mission_item_int_get_seq(
const mavlink_message_t* msg)
411 return _MAV_RETURN_uint16_t(msg, 28);
419static inline uint8_t mavlink_msg_mission_item_int_get_frame(
const mavlink_message_t* msg)
421 return _MAV_RETURN_uint8_t(msg, 34);
429static inline uint16_t mavlink_msg_mission_item_int_get_command(
const mavlink_message_t* msg)
431 return _MAV_RETURN_uint16_t(msg, 30);
439static inline uint8_t mavlink_msg_mission_item_int_get_current(
const mavlink_message_t* msg)
441 return _MAV_RETURN_uint8_t(msg, 35);
449static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(
const mavlink_message_t* msg)
451 return _MAV_RETURN_uint8_t(msg, 36);
459static inline float mavlink_msg_mission_item_int_get_param1(
const mavlink_message_t* msg)
461 return _MAV_RETURN_float(msg, 0);
469static inline float mavlink_msg_mission_item_int_get_param2(
const mavlink_message_t* msg)
471 return _MAV_RETURN_float(msg, 4);
479static inline float mavlink_msg_mission_item_int_get_param3(
const mavlink_message_t* msg)
481 return _MAV_RETURN_float(msg, 8);
489static inline float mavlink_msg_mission_item_int_get_param4(
const mavlink_message_t* msg)
491 return _MAV_RETURN_float(msg, 12);
499static inline int32_t mavlink_msg_mission_item_int_get_x(
const mavlink_message_t* msg)
501 return _MAV_RETURN_int32_t(msg, 16);
509static inline int32_t mavlink_msg_mission_item_int_get_y(
const mavlink_message_t* msg)
511 return _MAV_RETURN_int32_t(msg, 20);
519static inline float mavlink_msg_mission_item_int_get_z(
const mavlink_message_t* msg)
521 return _MAV_RETURN_float(msg, 24);
529static inline uint8_t mavlink_msg_mission_item_int_get_mission_type(
const mavlink_message_t* msg)
531 return _MAV_RETURN_uint8_t(msg, 37);
540static inline void mavlink_msg_mission_item_int_decode(
const mavlink_message_t* msg, mavlink_mission_item_int_t* mission_item_int)
542#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
543 mission_item_int->param1 = mavlink_msg_mission_item_int_get_param1(msg);
544 mission_item_int->param2 = mavlink_msg_mission_item_int_get_param2(msg);
545 mission_item_int->param3 = mavlink_msg_mission_item_int_get_param3(msg);
546 mission_item_int->param4 = mavlink_msg_mission_item_int_get_param4(msg);
547 mission_item_int->x = mavlink_msg_mission_item_int_get_x(msg);
548 mission_item_int->y = mavlink_msg_mission_item_int_get_y(msg);
549 mission_item_int->z = mavlink_msg_mission_item_int_get_z(msg);
550 mission_item_int->seq = mavlink_msg_mission_item_int_get_seq(msg);
551 mission_item_int->command = mavlink_msg_mission_item_int_get_command(msg);
552 mission_item_int->target_system = mavlink_msg_mission_item_int_get_target_system(msg);
553 mission_item_int->target_component = mavlink_msg_mission_item_int_get_target_component(msg);
554 mission_item_int->frame = mavlink_msg_mission_item_int_get_frame(msg);
555 mission_item_int->current = mavlink_msg_mission_item_int_get_current(msg);
556 mission_item_int->autocontinue = mavlink_msg_mission_item_int_get_autocontinue(msg);
557 mission_item_int->mission_type = mavlink_msg_mission_item_int_get_mission_type(msg);
559 uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;
560 memset(mission_item_int, 0, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
561 memcpy(mission_item_int, _MAV_PAYLOAD(msg), len);