mavlink_msg_rosflight_ins.h
Go to the documentation of this file.
1 // MESSAGE ROSFLIGHT_INS PACKING
2 
3 #define MAVLINK_MSG_ID_ROSFLIGHT_INS 194
4 
6 {
7  float pos_north; /*< */
8  float pos_east; /*< */
9  float pos_down; /*< */
10  float qw; /*< */
11  float qx; /*< */
12  float qy; /*< */
13  float qz; /*< */
14  float u; /*< */
15  float v; /*< */
16  float w; /*< */
17  float p; /*< */
18  float q; /*< */
19  float r; /*< */
21 
22 #define MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN 52
23 #define MAVLINK_MSG_ID_194_LEN 52
24 
25 #define MAVLINK_MSG_ID_ROSFLIGHT_INS_CRC 125
26 #define MAVLINK_MSG_ID_194_CRC 125
27 
28 
29 
30 #define MAVLINK_MESSAGE_INFO_ROSFLIGHT_INS { \
31  "ROSFLIGHT_INS", \
32  13, \
33  { { "pos_north", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rosflight_ins_t, pos_north) }, \
34  { "pos_east", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rosflight_ins_t, pos_east) }, \
35  { "pos_down", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_rosflight_ins_t, pos_down) }, \
36  { "qw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_rosflight_ins_t, qw) }, \
37  { "qx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_rosflight_ins_t, qx) }, \
38  { "qy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_rosflight_ins_t, qy) }, \
39  { "qz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_rosflight_ins_t, qz) }, \
40  { "u", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_rosflight_ins_t, u) }, \
41  { "v", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_rosflight_ins_t, v) }, \
42  { "w", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_rosflight_ins_t, w) }, \
43  { "p", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_rosflight_ins_t, p) }, \
44  { "q", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_rosflight_ins_t, q) }, \
45  { "r", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_rosflight_ins_t, r) }, \
46  } \
47 }
48 
49 
71 static inline uint16_t mavlink_msg_rosflight_ins_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
72  float pos_north, float pos_east, float pos_down, float qw, float qx, float qy, float qz, float u, float v, float w, float p, float q, float r)
73 {
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
76  _mav_put_float(buf, 0, pos_north);
77  _mav_put_float(buf, 4, pos_east);
78  _mav_put_float(buf, 8, pos_down);
79  _mav_put_float(buf, 12, qw);
80  _mav_put_float(buf, 16, qx);
81  _mav_put_float(buf, 20, qy);
82  _mav_put_float(buf, 24, qz);
83  _mav_put_float(buf, 28, u);
84  _mav_put_float(buf, 32, v);
85  _mav_put_float(buf, 36, w);
86  _mav_put_float(buf, 40, p);
87  _mav_put_float(buf, 44, q);
88  _mav_put_float(buf, 48, r);
89 
91 #else
93  packet.pos_north = pos_north;
94  packet.pos_east = pos_east;
95  packet.pos_down = pos_down;
96  packet.qw = qw;
97  packet.qx = qx;
98  packet.qy = qy;
99  packet.qz = qz;
100  packet.u = u;
101  packet.v = v;
102  packet.w = w;
103  packet.p = p;
104  packet.q = q;
105  packet.r = r;
106 
108 #endif
109 
110  msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_INS;
111 #if MAVLINK_CRC_EXTRA
113 #else
114  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN);
115 #endif
116 }
117 
139 static inline uint16_t mavlink_msg_rosflight_ins_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
140  mavlink_message_t* msg,
141  float pos_north,float pos_east,float pos_down,float qw,float qx,float qy,float qz,float u,float v,float w,float p,float q,float r)
142 {
143 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
145  _mav_put_float(buf, 0, pos_north);
146  _mav_put_float(buf, 4, pos_east);
147  _mav_put_float(buf, 8, pos_down);
148  _mav_put_float(buf, 12, qw);
149  _mav_put_float(buf, 16, qx);
150  _mav_put_float(buf, 20, qy);
151  _mav_put_float(buf, 24, qz);
152  _mav_put_float(buf, 28, u);
153  _mav_put_float(buf, 32, v);
154  _mav_put_float(buf, 36, w);
155  _mav_put_float(buf, 40, p);
156  _mav_put_float(buf, 44, q);
157  _mav_put_float(buf, 48, r);
158 
160 #else
162  packet.pos_north = pos_north;
163  packet.pos_east = pos_east;
164  packet.pos_down = pos_down;
165  packet.qw = qw;
166  packet.qx = qx;
167  packet.qy = qy;
168  packet.qz = qz;
169  packet.u = u;
170  packet.v = v;
171  packet.w = w;
172  packet.p = p;
173  packet.q = q;
174  packet.r = r;
175 
177 #endif
178 
179  msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_INS;
180 #if MAVLINK_CRC_EXTRA
182 #else
183  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN);
184 #endif
185 }
186 
195 static inline uint16_t mavlink_msg_rosflight_ins_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_ins_t* rosflight_ins)
196 {
197  return mavlink_msg_rosflight_ins_pack(system_id, component_id, msg, rosflight_ins->pos_north, rosflight_ins->pos_east, rosflight_ins->pos_down, rosflight_ins->qw, rosflight_ins->qx, rosflight_ins->qy, rosflight_ins->qz, rosflight_ins->u, rosflight_ins->v, rosflight_ins->w, rosflight_ins->p, rosflight_ins->q, rosflight_ins->r);
198 }
199 
209 static inline uint16_t mavlink_msg_rosflight_ins_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_ins_t* rosflight_ins)
210 {
211  return mavlink_msg_rosflight_ins_pack_chan(system_id, component_id, chan, msg, rosflight_ins->pos_north, rosflight_ins->pos_east, rosflight_ins->pos_down, rosflight_ins->qw, rosflight_ins->qx, rosflight_ins->qy, rosflight_ins->qz, rosflight_ins->u, rosflight_ins->v, rosflight_ins->w, rosflight_ins->p, rosflight_ins->q, rosflight_ins->r);
212 }
213 
232 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
233 
234 static inline void mavlink_msg_rosflight_ins_send(mavlink_channel_t chan, float pos_north, float pos_east, float pos_down, float qw, float qx, float qy, float qz, float u, float v, float w, float p, float q, float r)
235 {
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
238  _mav_put_float(buf, 0, pos_north);
239  _mav_put_float(buf, 4, pos_east);
240  _mav_put_float(buf, 8, pos_down);
241  _mav_put_float(buf, 12, qw);
242  _mav_put_float(buf, 16, qx);
243  _mav_put_float(buf, 20, qy);
244  _mav_put_float(buf, 24, qz);
245  _mav_put_float(buf, 28, u);
246  _mav_put_float(buf, 32, v);
247  _mav_put_float(buf, 36, w);
248  _mav_put_float(buf, 40, p);
249  _mav_put_float(buf, 44, q);
250  _mav_put_float(buf, 48, r);
251 
252 #if MAVLINK_CRC_EXTRA
254 #else
255  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_INS, buf, MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN);
256 #endif
257 #else
259  packet.pos_north = pos_north;
260  packet.pos_east = pos_east;
261  packet.pos_down = pos_down;
262  packet.qw = qw;
263  packet.qx = qx;
264  packet.qy = qy;
265  packet.qz = qz;
266  packet.u = u;
267  packet.v = v;
268  packet.w = w;
269  packet.p = p;
270  packet.q = q;
271  packet.r = r;
272 
273 #if MAVLINK_CRC_EXTRA
274  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_INS, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_INS_CRC);
275 #else
276  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_INS, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN);
277 #endif
278 #endif
279 }
280 
281 #if MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
282 /*
283  This varient of _send() can be used to save stack space by re-using
284  memory from the receive buffer. The caller provides a
285  mavlink_message_t which is the size of a full mavlink message. This
286  is usually the receive buffer for the channel, and allows a reply to an
287  incoming message with minimum stack space usage.
288  */
289 static inline void mavlink_msg_rosflight_ins_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float pos_north, float pos_east, float pos_down, float qw, float qx, float qy, float qz, float u, float v, float w, float p, float q, float r)
290 {
291 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
292  char *buf = (char *)msgbuf;
293  _mav_put_float(buf, 0, pos_north);
294  _mav_put_float(buf, 4, pos_east);
295  _mav_put_float(buf, 8, pos_down);
296  _mav_put_float(buf, 12, qw);
297  _mav_put_float(buf, 16, qx);
298  _mav_put_float(buf, 20, qy);
299  _mav_put_float(buf, 24, qz);
300  _mav_put_float(buf, 28, u);
301  _mav_put_float(buf, 32, v);
302  _mav_put_float(buf, 36, w);
303  _mav_put_float(buf, 40, p);
304  _mav_put_float(buf, 44, q);
305  _mav_put_float(buf, 48, r);
306 
307 #if MAVLINK_CRC_EXTRA
309 #else
310  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_INS, buf, MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN);
311 #endif
312 #else
314  packet->pos_north = pos_north;
315  packet->pos_east = pos_east;
316  packet->pos_down = pos_down;
317  packet->qw = qw;
318  packet->qx = qx;
319  packet->qy = qy;
320  packet->qz = qz;
321  packet->u = u;
322  packet->v = v;
323  packet->w = w;
324  packet->p = p;
325  packet->q = q;
326  packet->r = r;
327 
328 #if MAVLINK_CRC_EXTRA
329  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_INS, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_INS_CRC);
330 #else
331  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_INS, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN);
332 #endif
333 #endif
334 }
335 #endif
336 
337 #endif
338 
339 // MESSAGE ROSFLIGHT_INS UNPACKING
340 
341 
347 static inline float mavlink_msg_rosflight_ins_get_pos_north(const mavlink_message_t* msg)
348 {
349  return _MAV_RETURN_float(msg, 0);
350 }
351 
357 static inline float mavlink_msg_rosflight_ins_get_pos_east(const mavlink_message_t* msg)
358 {
359  return _MAV_RETURN_float(msg, 4);
360 }
361 
367 static inline float mavlink_msg_rosflight_ins_get_pos_down(const mavlink_message_t* msg)
368 {
369  return _MAV_RETURN_float(msg, 8);
370 }
371 
377 static inline float mavlink_msg_rosflight_ins_get_qw(const mavlink_message_t* msg)
378 {
379  return _MAV_RETURN_float(msg, 12);
380 }
381 
387 static inline float mavlink_msg_rosflight_ins_get_qx(const mavlink_message_t* msg)
388 {
389  return _MAV_RETURN_float(msg, 16);
390 }
391 
397 static inline float mavlink_msg_rosflight_ins_get_qy(const mavlink_message_t* msg)
398 {
399  return _MAV_RETURN_float(msg, 20);
400 }
401 
407 static inline float mavlink_msg_rosflight_ins_get_qz(const mavlink_message_t* msg)
408 {
409  return _MAV_RETURN_float(msg, 24);
410 }
411 
417 static inline float mavlink_msg_rosflight_ins_get_u(const mavlink_message_t* msg)
418 {
419  return _MAV_RETURN_float(msg, 28);
420 }
421 
427 static inline float mavlink_msg_rosflight_ins_get_v(const mavlink_message_t* msg)
428 {
429  return _MAV_RETURN_float(msg, 32);
430 }
431 
437 static inline float mavlink_msg_rosflight_ins_get_w(const mavlink_message_t* msg)
438 {
439  return _MAV_RETURN_float(msg, 36);
440 }
441 
447 static inline float mavlink_msg_rosflight_ins_get_p(const mavlink_message_t* msg)
448 {
449  return _MAV_RETURN_float(msg, 40);
450 }
451 
457 static inline float mavlink_msg_rosflight_ins_get_q(const mavlink_message_t* msg)
458 {
459  return _MAV_RETURN_float(msg, 44);
460 }
461 
467 static inline float mavlink_msg_rosflight_ins_get_r(const mavlink_message_t* msg)
468 {
469  return _MAV_RETURN_float(msg, 48);
470 }
471 
478 static inline void mavlink_msg_rosflight_ins_decode(const mavlink_message_t* msg, mavlink_rosflight_ins_t* rosflight_ins)
479 {
480 #if MAVLINK_NEED_BYTE_SWAP
482  rosflight_ins->pos_east = mavlink_msg_rosflight_ins_get_pos_east(msg);
483  rosflight_ins->pos_down = mavlink_msg_rosflight_ins_get_pos_down(msg);
484  rosflight_ins->qw = mavlink_msg_rosflight_ins_get_qw(msg);
485  rosflight_ins->qx = mavlink_msg_rosflight_ins_get_qx(msg);
486  rosflight_ins->qy = mavlink_msg_rosflight_ins_get_qy(msg);
487  rosflight_ins->qz = mavlink_msg_rosflight_ins_get_qz(msg);
488  rosflight_ins->u = mavlink_msg_rosflight_ins_get_u(msg);
489  rosflight_ins->v = mavlink_msg_rosflight_ins_get_v(msg);
490  rosflight_ins->w = mavlink_msg_rosflight_ins_get_w(msg);
491  rosflight_ins->p = mavlink_msg_rosflight_ins_get_p(msg);
492  rosflight_ins->q = mavlink_msg_rosflight_ins_get_q(msg);
493  rosflight_ins->r = mavlink_msg_rosflight_ins_get_r(msg);
494 #else
495  memcpy(rosflight_ins, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN);
496 #endif
497 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:25