mavlink_msg_mission_item.h
Go to the documentation of this file.
1 // MESSAGE MISSION_ITEM PACKING
2 
3 #define MAVLINK_MSG_ID_MISSION_ITEM 39
4 
6 {
7  float param1; /*< PARAM1, see MAV_CMD enum*/
8  float param2; /*< PARAM2, see MAV_CMD enum*/
9  float param3; /*< PARAM3, see MAV_CMD enum*/
10  float param4; /*< PARAM4, see MAV_CMD enum*/
11  float x; /*< PARAM5 / local: x position, global: latitude*/
12  float y; /*< PARAM6 / y position: global: longitude*/
13  float z; /*< PARAM7 / z position: global: altitude (relative or absolute, depending on frame.*/
14  uint16_t seq; /*< Sequence*/
15  uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/
16  uint8_t target_system; /*< System ID*/
17  uint8_t target_component; /*< Component ID*/
18  uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/
19  uint8_t current; /*< false:0, true:1*/
20  uint8_t autocontinue; /*< autocontinue to next wp*/
22 
23 #define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37
24 #define MAVLINK_MSG_ID_39_LEN 37
25 
26 #define MAVLINK_MSG_ID_MISSION_ITEM_CRC 254
27 #define MAVLINK_MSG_ID_39_CRC 254
28 
29 
30 
31 #define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \
32  "MISSION_ITEM", \
33  14, \
34  { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \
35  { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \
36  { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \
37  { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \
38  { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \
39  { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \
40  { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \
41  { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \
42  { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \
43  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \
44  { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \
45  { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \
46  { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \
47  { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \
48  } \
49 }
50 
51 
74 static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
75  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, float x, float y, float z)
76 {
77 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
79  _mav_put_float(buf, 0, param1);
80  _mav_put_float(buf, 4, param2);
81  _mav_put_float(buf, 8, param3);
82  _mav_put_float(buf, 12, param4);
83  _mav_put_float(buf, 16, x);
84  _mav_put_float(buf, 20, y);
85  _mav_put_float(buf, 24, z);
86  _mav_put_uint16_t(buf, 28, seq);
87  _mav_put_uint16_t(buf, 30, command);
88  _mav_put_uint8_t(buf, 32, target_system);
89  _mav_put_uint8_t(buf, 33, target_component);
90  _mav_put_uint8_t(buf, 34, frame);
91  _mav_put_uint8_t(buf, 35, current);
92  _mav_put_uint8_t(buf, 36, autocontinue);
93 
95 #else
97  packet.param1 = param1;
98  packet.param2 = param2;
99  packet.param3 = param3;
100  packet.param4 = param4;
101  packet.x = x;
102  packet.y = y;
103  packet.z = z;
104  packet.seq = seq;
105  packet.command = command;
106  packet.target_system = target_system;
108  packet.frame = frame;
109  packet.current = current;
110  packet.autocontinue = autocontinue;
111 
113 #endif
114 
115  msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM;
116 #if MAVLINK_CRC_EXTRA
118 #else
119  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
120 #endif
121 }
122 
145 static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
146  mavlink_message_t* msg,
147  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,float x,float y,float z)
148 {
149 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
151  _mav_put_float(buf, 0, param1);
152  _mav_put_float(buf, 4, param2);
153  _mav_put_float(buf, 8, param3);
154  _mav_put_float(buf, 12, param4);
155  _mav_put_float(buf, 16, x);
156  _mav_put_float(buf, 20, y);
157  _mav_put_float(buf, 24, z);
158  _mav_put_uint16_t(buf, 28, seq);
159  _mav_put_uint16_t(buf, 30, command);
160  _mav_put_uint8_t(buf, 32, target_system);
161  _mav_put_uint8_t(buf, 33, target_component);
162  _mav_put_uint8_t(buf, 34, frame);
163  _mav_put_uint8_t(buf, 35, current);
164  _mav_put_uint8_t(buf, 36, autocontinue);
165 
167 #else
168  mavlink_mission_item_t packet;
169  packet.param1 = param1;
170  packet.param2 = param2;
171  packet.param3 = param3;
172  packet.param4 = param4;
173  packet.x = x;
174  packet.y = y;
175  packet.z = z;
176  packet.seq = seq;
177  packet.command = command;
178  packet.target_system = target_system;
180  packet.frame = frame;
181  packet.current = current;
182  packet.autocontinue = autocontinue;
183 
185 #endif
186 
187  msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM;
188 #if MAVLINK_CRC_EXTRA
190 #else
191  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
192 #endif
193 }
194 
203 static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item)
204 {
205  return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z);
206 }
207 
217 static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item)
218 {
219  return mavlink_msg_mission_item_pack_chan(system_id, component_id, chan, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z);
220 }
221 
241 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
242 
243 static inline void mavlink_msg_mission_item_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, float x, float y, float z)
244 {
245 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
247  _mav_put_float(buf, 0, param1);
248  _mav_put_float(buf, 4, param2);
249  _mav_put_float(buf, 8, param3);
250  _mav_put_float(buf, 12, param4);
251  _mav_put_float(buf, 16, x);
252  _mav_put_float(buf, 20, y);
253  _mav_put_float(buf, 24, z);
254  _mav_put_uint16_t(buf, 28, seq);
255  _mav_put_uint16_t(buf, 30, command);
258  _mav_put_uint8_t(buf, 34, frame);
259  _mav_put_uint8_t(buf, 35, current);
260  _mav_put_uint8_t(buf, 36, autocontinue);
261 
262 #if MAVLINK_CRC_EXTRA
264 #else
265  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
266 #endif
267 #else
268  mavlink_mission_item_t packet;
269  packet.param1 = param1;
270  packet.param2 = param2;
271  packet.param3 = param3;
272  packet.param4 = param4;
273  packet.x = x;
274  packet.y = y;
275  packet.z = z;
276  packet.seq = seq;
277  packet.command = command;
278  packet.target_system = target_system;
280  packet.frame = frame;
281  packet.current = current;
282  packet.autocontinue = autocontinue;
283 
284 #if MAVLINK_CRC_EXTRA
285  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
286 #else
287  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
288 #endif
289 #endif
290 }
291 
292 #if MAVLINK_MSG_ID_MISSION_ITEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
293 /*
294  This varient of _send() can be used to save stack space by re-using
295  memory from the receive buffer. The caller provides a
296  mavlink_message_t which is the size of a full mavlink message. This
297  is usually the receive buffer for the channel, and allows a reply to an
298  incoming message with minimum stack space usage.
299  */
300 static inline void mavlink_msg_mission_item_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, float x, float y, float z)
301 {
302 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
303  char *buf = (char *)msgbuf;
304  _mav_put_float(buf, 0, param1);
305  _mav_put_float(buf, 4, param2);
306  _mav_put_float(buf, 8, param3);
307  _mav_put_float(buf, 12, param4);
308  _mav_put_float(buf, 16, x);
309  _mav_put_float(buf, 20, y);
310  _mav_put_float(buf, 24, z);
311  _mav_put_uint16_t(buf, 28, seq);
312  _mav_put_uint16_t(buf, 30, command);
315  _mav_put_uint8_t(buf, 34, frame);
316  _mav_put_uint8_t(buf, 35, current);
317  _mav_put_uint8_t(buf, 36, autocontinue);
318 
319 #if MAVLINK_CRC_EXTRA
321 #else
322  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
323 #endif
324 #else
326  packet->param1 = param1;
327  packet->param2 = param2;
328  packet->param3 = param3;
329  packet->param4 = param4;
330  packet->x = x;
331  packet->y = y;
332  packet->z = z;
333  packet->seq = seq;
334  packet->command = command;
335  packet->target_system = target_system;
337  packet->frame = frame;
338  packet->current = current;
339  packet->autocontinue = autocontinue;
340 
341 #if MAVLINK_CRC_EXTRA
342  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
343 #else
344  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
345 #endif
346 #endif
347 }
348 #endif
349 
350 #endif
351 
352 // MESSAGE MISSION_ITEM UNPACKING
353 
354 
360 static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg)
361 {
362  return _MAV_RETURN_uint8_t(msg, 32);
363 }
364 
370 static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg)
371 {
372  return _MAV_RETURN_uint8_t(msg, 33);
373 }
374 
380 static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg)
381 {
382  return _MAV_RETURN_uint16_t(msg, 28);
383 }
384 
390 static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg)
391 {
392  return _MAV_RETURN_uint8_t(msg, 34);
393 }
394 
400 static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg)
401 {
402  return _MAV_RETURN_uint16_t(msg, 30);
403 }
404 
410 static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg)
411 {
412  return _MAV_RETURN_uint8_t(msg, 35);
413 }
414 
420 static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg)
421 {
422  return _MAV_RETURN_uint8_t(msg, 36);
423 }
424 
430 static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg)
431 {
432  return _MAV_RETURN_float(msg, 0);
433 }
434 
440 static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg)
441 {
442  return _MAV_RETURN_float(msg, 4);
443 }
444 
450 static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg)
451 {
452  return _MAV_RETURN_float(msg, 8);
453 }
454 
460 static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg)
461 {
462  return _MAV_RETURN_float(msg, 12);
463 }
464 
470 static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg)
471 {
472  return _MAV_RETURN_float(msg, 16);
473 }
474 
480 static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg)
481 {
482  return _MAV_RETURN_float(msg, 20);
483 }
484 
490 static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg)
491 {
492  return _MAV_RETURN_float(msg, 24);
493 }
494 
501 static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mavlink_mission_item_t* mission_item)
502 {
503 #if MAVLINK_NEED_BYTE_SWAP
504  mission_item->param1 = mavlink_msg_mission_item_get_param1(msg);
505  mission_item->param2 = mavlink_msg_mission_item_get_param2(msg);
506  mission_item->param3 = mavlink_msg_mission_item_get_param3(msg);
507  mission_item->param4 = mavlink_msg_mission_item_get_param4(msg);
508  mission_item->x = mavlink_msg_mission_item_get_x(msg);
509  mission_item->y = mavlink_msg_mission_item_get_y(msg);
510  mission_item->z = mavlink_msg_mission_item_get_z(msg);
511  mission_item->seq = mavlink_msg_mission_item_get_seq(msg);
512  mission_item->command = mavlink_msg_mission_item_get_command(msg);
515  mission_item->frame = mavlink_msg_mission_item_get_frame(msg);
516  mission_item->current = mavlink_msg_mission_item_get_current(msg);
518 #else
519  memcpy(mission_item, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_LEN);
520 #endif
521 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:145


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:47