mavlink_msg_rosflight_gnss.h
Go to the documentation of this file.
1 // MESSAGE ROSFLIGHT_GNSS PACKING
2 
3 #define MAVLINK_MSG_ID_ROSFLIGHT_GNSS 197
4 
6 {
7  uint64_t time; /*< */
8  uint64_t nanos; /*< */
9  uint64_t rosflight_timestamp; /*< */
10  uint32_t time_of_week; /*< */
11  int32_t lat; /*< */
12  int32_t lon; /*< */
13  int32_t height; /*< */
14  int32_t vel_n; /*< */
15  int32_t vel_e; /*< */
16  int32_t vel_d; /*< */
17  uint32_t h_acc; /*< */
18  uint32_t v_acc; /*< */
19  int32_t ecef_x; /*< */
20  int32_t ecef_y; /*< */
21  int32_t ecef_z; /*< */
22  uint32_t p_acc; /*< */
23  int32_t ecef_v_x; /*< */
24  int32_t ecef_v_y; /*< */
25  int32_t ecef_v_z; /*< */
26  uint32_t s_acc; /*< */
27  uint8_t fix_type; /*< */
29 
30 #define MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN 93
31 #define MAVLINK_MSG_ID_197_LEN 93
32 
33 #define MAVLINK_MSG_ID_ROSFLIGHT_GNSS_CRC 9
34 #define MAVLINK_MSG_ID_197_CRC 9
35 
36 
37 
38 #define MAVLINK_MESSAGE_INFO_ROSFLIGHT_GNSS { \
39  "ROSFLIGHT_GNSS", \
40  21, \
41  { { "time", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rosflight_gnss_t, time) }, \
42  { "nanos", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_rosflight_gnss_t, nanos) }, \
43  { "rosflight_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_rosflight_gnss_t, rosflight_timestamp) }, \
44  { "time_of_week", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_rosflight_gnss_t, time_of_week) }, \
45  { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_rosflight_gnss_t, lat) }, \
46  { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_rosflight_gnss_t, lon) }, \
47  { "height", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_rosflight_gnss_t, height) }, \
48  { "vel_n", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_rosflight_gnss_t, vel_n) }, \
49  { "vel_e", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_rosflight_gnss_t, vel_e) }, \
50  { "vel_d", NULL, MAVLINK_TYPE_INT32_T, 0, 48, offsetof(mavlink_rosflight_gnss_t, vel_d) }, \
51  { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 52, offsetof(mavlink_rosflight_gnss_t, h_acc) }, \
52  { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 56, offsetof(mavlink_rosflight_gnss_t, v_acc) }, \
53  { "ecef_x", NULL, MAVLINK_TYPE_INT32_T, 0, 60, offsetof(mavlink_rosflight_gnss_t, ecef_x) }, \
54  { "ecef_y", NULL, MAVLINK_TYPE_INT32_T, 0, 64, offsetof(mavlink_rosflight_gnss_t, ecef_y) }, \
55  { "ecef_z", NULL, MAVLINK_TYPE_INT32_T, 0, 68, offsetof(mavlink_rosflight_gnss_t, ecef_z) }, \
56  { "p_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 72, offsetof(mavlink_rosflight_gnss_t, p_acc) }, \
57  { "ecef_v_x", NULL, MAVLINK_TYPE_INT32_T, 0, 76, offsetof(mavlink_rosflight_gnss_t, ecef_v_x) }, \
58  { "ecef_v_y", NULL, MAVLINK_TYPE_INT32_T, 0, 80, offsetof(mavlink_rosflight_gnss_t, ecef_v_y) }, \
59  { "ecef_v_z", NULL, MAVLINK_TYPE_INT32_T, 0, 84, offsetof(mavlink_rosflight_gnss_t, ecef_v_z) }, \
60  { "s_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 88, offsetof(mavlink_rosflight_gnss_t, s_acc) }, \
61  { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_rosflight_gnss_t, fix_type) }, \
62  } \
63 }
64 
65 
95 static inline uint16_t mavlink_msg_rosflight_gnss_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
96  uint32_t time_of_week, uint8_t fix_type, uint64_t time, uint64_t nanos, int32_t lat, int32_t lon, int32_t height, int32_t vel_n, int32_t vel_e, int32_t vel_d, uint32_t h_acc, uint32_t v_acc, int32_t ecef_x, int32_t ecef_y, int32_t ecef_z, uint32_t p_acc, int32_t ecef_v_x, int32_t ecef_v_y, int32_t ecef_v_z, uint32_t s_acc, uint64_t rosflight_timestamp)
97 {
98 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
100  _mav_put_uint64_t(buf, 0, time);
101  _mav_put_uint64_t(buf, 8, nanos);
102  _mav_put_uint64_t(buf, 16, rosflight_timestamp);
103  _mav_put_uint32_t(buf, 24, time_of_week);
104  _mav_put_int32_t(buf, 28, lat);
105  _mav_put_int32_t(buf, 32, lon);
106  _mav_put_int32_t(buf, 36, height);
107  _mav_put_int32_t(buf, 40, vel_n);
108  _mav_put_int32_t(buf, 44, vel_e);
109  _mav_put_int32_t(buf, 48, vel_d);
110  _mav_put_uint32_t(buf, 52, h_acc);
111  _mav_put_uint32_t(buf, 56, v_acc);
112  _mav_put_int32_t(buf, 60, ecef_x);
113  _mav_put_int32_t(buf, 64, ecef_y);
114  _mav_put_int32_t(buf, 68, ecef_z);
115  _mav_put_uint32_t(buf, 72, p_acc);
116  _mav_put_int32_t(buf, 76, ecef_v_x);
117  _mav_put_int32_t(buf, 80, ecef_v_y);
118  _mav_put_int32_t(buf, 84, ecef_v_z);
119  _mav_put_uint32_t(buf, 88, s_acc);
120  _mav_put_uint8_t(buf, 92, fix_type);
121 
123 #else
125  packet.time = time;
126  packet.nanos = nanos;
128  packet.time_of_week = time_of_week;
129  packet.lat = lat;
130  packet.lon = lon;
131  packet.height = height;
132  packet.vel_n = vel_n;
133  packet.vel_e = vel_e;
134  packet.vel_d = vel_d;
135  packet.h_acc = h_acc;
136  packet.v_acc = v_acc;
137  packet.ecef_x = ecef_x;
138  packet.ecef_y = ecef_y;
139  packet.ecef_z = ecef_z;
140  packet.p_acc = p_acc;
141  packet.ecef_v_x = ecef_v_x;
142  packet.ecef_v_y = ecef_v_y;
143  packet.ecef_v_z = ecef_v_z;
144  packet.s_acc = s_acc;
145  packet.fix_type = fix_type;
146 
148 #endif
149 
150  msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_GNSS;
151 #if MAVLINK_CRC_EXTRA
153 #else
154  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN);
155 #endif
156 }
157 
187 static inline uint16_t mavlink_msg_rosflight_gnss_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
188  mavlink_message_t* msg,
189  uint32_t time_of_week,uint8_t fix_type,uint64_t time,uint64_t nanos,int32_t lat,int32_t lon,int32_t height,int32_t vel_n,int32_t vel_e,int32_t vel_d,uint32_t h_acc,uint32_t v_acc,int32_t ecef_x,int32_t ecef_y,int32_t ecef_z,uint32_t p_acc,int32_t ecef_v_x,int32_t ecef_v_y,int32_t ecef_v_z,uint32_t s_acc,uint64_t rosflight_timestamp)
190 {
191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193  _mav_put_uint64_t(buf, 0, time);
194  _mav_put_uint64_t(buf, 8, nanos);
195  _mav_put_uint64_t(buf, 16, rosflight_timestamp);
196  _mav_put_uint32_t(buf, 24, time_of_week);
197  _mav_put_int32_t(buf, 28, lat);
198  _mav_put_int32_t(buf, 32, lon);
199  _mav_put_int32_t(buf, 36, height);
200  _mav_put_int32_t(buf, 40, vel_n);
201  _mav_put_int32_t(buf, 44, vel_e);
202  _mav_put_int32_t(buf, 48, vel_d);
203  _mav_put_uint32_t(buf, 52, h_acc);
204  _mav_put_uint32_t(buf, 56, v_acc);
205  _mav_put_int32_t(buf, 60, ecef_x);
206  _mav_put_int32_t(buf, 64, ecef_y);
207  _mav_put_int32_t(buf, 68, ecef_z);
208  _mav_put_uint32_t(buf, 72, p_acc);
209  _mav_put_int32_t(buf, 76, ecef_v_x);
210  _mav_put_int32_t(buf, 80, ecef_v_y);
211  _mav_put_int32_t(buf, 84, ecef_v_z);
212  _mav_put_uint32_t(buf, 88, s_acc);
213  _mav_put_uint8_t(buf, 92, fix_type);
214 
216 #else
218  packet.time = time;
219  packet.nanos = nanos;
221  packet.time_of_week = time_of_week;
222  packet.lat = lat;
223  packet.lon = lon;
224  packet.height = height;
225  packet.vel_n = vel_n;
226  packet.vel_e = vel_e;
227  packet.vel_d = vel_d;
228  packet.h_acc = h_acc;
229  packet.v_acc = v_acc;
230  packet.ecef_x = ecef_x;
231  packet.ecef_y = ecef_y;
232  packet.ecef_z = ecef_z;
233  packet.p_acc = p_acc;
234  packet.ecef_v_x = ecef_v_x;
235  packet.ecef_v_y = ecef_v_y;
236  packet.ecef_v_z = ecef_v_z;
237  packet.s_acc = s_acc;
238  packet.fix_type = fix_type;
239 
241 #endif
242 
243  msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_GNSS;
244 #if MAVLINK_CRC_EXTRA
246 #else
247  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN);
248 #endif
249 }
250 
259 static inline uint16_t mavlink_msg_rosflight_gnss_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_gnss_t* rosflight_gnss)
260 {
261  return mavlink_msg_rosflight_gnss_pack(system_id, component_id, msg, rosflight_gnss->time_of_week, rosflight_gnss->fix_type, rosflight_gnss->time, rosflight_gnss->nanos, rosflight_gnss->lat, rosflight_gnss->lon, rosflight_gnss->height, rosflight_gnss->vel_n, rosflight_gnss->vel_e, rosflight_gnss->vel_d, rosflight_gnss->h_acc, rosflight_gnss->v_acc, rosflight_gnss->ecef_x, rosflight_gnss->ecef_y, rosflight_gnss->ecef_z, rosflight_gnss->p_acc, rosflight_gnss->ecef_v_x, rosflight_gnss->ecef_v_y, rosflight_gnss->ecef_v_z, rosflight_gnss->s_acc, rosflight_gnss->rosflight_timestamp);
262 }
263 
273 static inline uint16_t mavlink_msg_rosflight_gnss_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_gnss_t* rosflight_gnss)
274 {
275  return mavlink_msg_rosflight_gnss_pack_chan(system_id, component_id, chan, msg, rosflight_gnss->time_of_week, rosflight_gnss->fix_type, rosflight_gnss->time, rosflight_gnss->nanos, rosflight_gnss->lat, rosflight_gnss->lon, rosflight_gnss->height, rosflight_gnss->vel_n, rosflight_gnss->vel_e, rosflight_gnss->vel_d, rosflight_gnss->h_acc, rosflight_gnss->v_acc, rosflight_gnss->ecef_x, rosflight_gnss->ecef_y, rosflight_gnss->ecef_z, rosflight_gnss->p_acc, rosflight_gnss->ecef_v_x, rosflight_gnss->ecef_v_y, rosflight_gnss->ecef_v_z, rosflight_gnss->s_acc, rosflight_gnss->rosflight_timestamp);
276 }
277 
304 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
305 
306 static inline void mavlink_msg_rosflight_gnss_send(mavlink_channel_t chan, uint32_t time_of_week, uint8_t fix_type, uint64_t time, uint64_t nanos, int32_t lat, int32_t lon, int32_t height, int32_t vel_n, int32_t vel_e, int32_t vel_d, uint32_t h_acc, uint32_t v_acc, int32_t ecef_x, int32_t ecef_y, int32_t ecef_z, uint32_t p_acc, int32_t ecef_v_x, int32_t ecef_v_y, int32_t ecef_v_z, uint32_t s_acc, uint64_t rosflight_timestamp)
307 {
308 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
310  _mav_put_uint64_t(buf, 0, time);
311  _mav_put_uint64_t(buf, 8, nanos);
312  _mav_put_uint64_t(buf, 16, rosflight_timestamp);
314  _mav_put_int32_t(buf, 28, lat);
315  _mav_put_int32_t(buf, 32, lon);
316  _mav_put_int32_t(buf, 36, height);
317  _mav_put_int32_t(buf, 40, vel_n);
318  _mav_put_int32_t(buf, 44, vel_e);
319  _mav_put_int32_t(buf, 48, vel_d);
320  _mav_put_uint32_t(buf, 52, h_acc);
321  _mav_put_uint32_t(buf, 56, v_acc);
322  _mav_put_int32_t(buf, 60, ecef_x);
323  _mav_put_int32_t(buf, 64, ecef_y);
324  _mav_put_int32_t(buf, 68, ecef_z);
325  _mav_put_uint32_t(buf, 72, p_acc);
326  _mav_put_int32_t(buf, 76, ecef_v_x);
327  _mav_put_int32_t(buf, 80, ecef_v_y);
328  _mav_put_int32_t(buf, 84, ecef_v_z);
329  _mav_put_uint32_t(buf, 88, s_acc);
330  _mav_put_uint8_t(buf, 92, fix_type);
331 
332 #if MAVLINK_CRC_EXTRA
334 #else
335  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS, buf, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN);
336 #endif
337 #else
339  packet.time = time;
340  packet.nanos = nanos;
342  packet.time_of_week = time_of_week;
343  packet.lat = lat;
344  packet.lon = lon;
345  packet.height = height;
346  packet.vel_n = vel_n;
347  packet.vel_e = vel_e;
348  packet.vel_d = vel_d;
349  packet.h_acc = h_acc;
350  packet.v_acc = v_acc;
351  packet.ecef_x = ecef_x;
352  packet.ecef_y = ecef_y;
353  packet.ecef_z = ecef_z;
354  packet.p_acc = p_acc;
355  packet.ecef_v_x = ecef_v_x;
356  packet.ecef_v_y = ecef_v_y;
357  packet.ecef_v_z = ecef_v_z;
358  packet.s_acc = s_acc;
359  packet.fix_type = fix_type;
360 
361 #if MAVLINK_CRC_EXTRA
362  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_CRC);
363 #else
364  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN);
365 #endif
366 #endif
367 }
368 
369 #if MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
370 /*
371  This varient of _send() can be used to save stack space by re-using
372  memory from the receive buffer. The caller provides a
373  mavlink_message_t which is the size of a full mavlink message. This
374  is usually the receive buffer for the channel, and allows a reply to an
375  incoming message with minimum stack space usage.
376  */
377 static inline void mavlink_msg_rosflight_gnss_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_of_week, uint8_t fix_type, uint64_t time, uint64_t nanos, int32_t lat, int32_t lon, int32_t height, int32_t vel_n, int32_t vel_e, int32_t vel_d, uint32_t h_acc, uint32_t v_acc, int32_t ecef_x, int32_t ecef_y, int32_t ecef_z, uint32_t p_acc, int32_t ecef_v_x, int32_t ecef_v_y, int32_t ecef_v_z, uint32_t s_acc, uint64_t rosflight_timestamp)
378 {
379 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
380  char *buf = (char *)msgbuf;
381  _mav_put_uint64_t(buf, 0, time);
382  _mav_put_uint64_t(buf, 8, nanos);
383  _mav_put_uint64_t(buf, 16, rosflight_timestamp);
385  _mav_put_int32_t(buf, 28, lat);
386  _mav_put_int32_t(buf, 32, lon);
387  _mav_put_int32_t(buf, 36, height);
388  _mav_put_int32_t(buf, 40, vel_n);
389  _mav_put_int32_t(buf, 44, vel_e);
390  _mav_put_int32_t(buf, 48, vel_d);
391  _mav_put_uint32_t(buf, 52, h_acc);
392  _mav_put_uint32_t(buf, 56, v_acc);
393  _mav_put_int32_t(buf, 60, ecef_x);
394  _mav_put_int32_t(buf, 64, ecef_y);
395  _mav_put_int32_t(buf, 68, ecef_z);
396  _mav_put_uint32_t(buf, 72, p_acc);
397  _mav_put_int32_t(buf, 76, ecef_v_x);
398  _mav_put_int32_t(buf, 80, ecef_v_y);
399  _mav_put_int32_t(buf, 84, ecef_v_z);
400  _mav_put_uint32_t(buf, 88, s_acc);
401  _mav_put_uint8_t(buf, 92, fix_type);
402 
403 #if MAVLINK_CRC_EXTRA
405 #else
406  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS, buf, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN);
407 #endif
408 #else
410  packet->time = time;
411  packet->nanos = nanos;
413  packet->time_of_week = time_of_week;
414  packet->lat = lat;
415  packet->lon = lon;
416  packet->height = height;
417  packet->vel_n = vel_n;
418  packet->vel_e = vel_e;
419  packet->vel_d = vel_d;
420  packet->h_acc = h_acc;
421  packet->v_acc = v_acc;
422  packet->ecef_x = ecef_x;
423  packet->ecef_y = ecef_y;
424  packet->ecef_z = ecef_z;
425  packet->p_acc = p_acc;
426  packet->ecef_v_x = ecef_v_x;
427  packet->ecef_v_y = ecef_v_y;
428  packet->ecef_v_z = ecef_v_z;
429  packet->s_acc = s_acc;
430  packet->fix_type = fix_type;
431 
432 #if MAVLINK_CRC_EXTRA
433  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_CRC);
434 #else
435  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_GNSS, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN);
436 #endif
437 #endif
438 }
439 #endif
440 
441 #endif
442 
443 // MESSAGE ROSFLIGHT_GNSS UNPACKING
444 
445 
451 static inline uint32_t mavlink_msg_rosflight_gnss_get_time_of_week(const mavlink_message_t* msg)
452 {
453  return _MAV_RETURN_uint32_t(msg, 24);
454 }
455 
461 static inline uint8_t mavlink_msg_rosflight_gnss_get_fix_type(const mavlink_message_t* msg)
462 {
463  return _MAV_RETURN_uint8_t(msg, 92);
464 }
465 
471 static inline uint64_t mavlink_msg_rosflight_gnss_get_time(const mavlink_message_t* msg)
472 {
473  return _MAV_RETURN_uint64_t(msg, 0);
474 }
475 
481 static inline uint64_t mavlink_msg_rosflight_gnss_get_nanos(const mavlink_message_t* msg)
482 {
483  return _MAV_RETURN_uint64_t(msg, 8);
484 }
485 
491 static inline int32_t mavlink_msg_rosflight_gnss_get_lat(const mavlink_message_t* msg)
492 {
493  return _MAV_RETURN_int32_t(msg, 28);
494 }
495 
501 static inline int32_t mavlink_msg_rosflight_gnss_get_lon(const mavlink_message_t* msg)
502 {
503  return _MAV_RETURN_int32_t(msg, 32);
504 }
505 
511 static inline int32_t mavlink_msg_rosflight_gnss_get_height(const mavlink_message_t* msg)
512 {
513  return _MAV_RETURN_int32_t(msg, 36);
514 }
515 
521 static inline int32_t mavlink_msg_rosflight_gnss_get_vel_n(const mavlink_message_t* msg)
522 {
523  return _MAV_RETURN_int32_t(msg, 40);
524 }
525 
531 static inline int32_t mavlink_msg_rosflight_gnss_get_vel_e(const mavlink_message_t* msg)
532 {
533  return _MAV_RETURN_int32_t(msg, 44);
534 }
535 
541 static inline int32_t mavlink_msg_rosflight_gnss_get_vel_d(const mavlink_message_t* msg)
542 {
543  return _MAV_RETURN_int32_t(msg, 48);
544 }
545 
551 static inline uint32_t mavlink_msg_rosflight_gnss_get_h_acc(const mavlink_message_t* msg)
552 {
553  return _MAV_RETURN_uint32_t(msg, 52);
554 }
555 
561 static inline uint32_t mavlink_msg_rosflight_gnss_get_v_acc(const mavlink_message_t* msg)
562 {
563  return _MAV_RETURN_uint32_t(msg, 56);
564 }
565 
571 static inline int32_t mavlink_msg_rosflight_gnss_get_ecef_x(const mavlink_message_t* msg)
572 {
573  return _MAV_RETURN_int32_t(msg, 60);
574 }
575 
581 static inline int32_t mavlink_msg_rosflight_gnss_get_ecef_y(const mavlink_message_t* msg)
582 {
583  return _MAV_RETURN_int32_t(msg, 64);
584 }
585 
591 static inline int32_t mavlink_msg_rosflight_gnss_get_ecef_z(const mavlink_message_t* msg)
592 {
593  return _MAV_RETURN_int32_t(msg, 68);
594 }
595 
601 static inline uint32_t mavlink_msg_rosflight_gnss_get_p_acc(const mavlink_message_t* msg)
602 {
603  return _MAV_RETURN_uint32_t(msg, 72);
604 }
605 
611 static inline int32_t mavlink_msg_rosflight_gnss_get_ecef_v_x(const mavlink_message_t* msg)
612 {
613  return _MAV_RETURN_int32_t(msg, 76);
614 }
615 
621 static inline int32_t mavlink_msg_rosflight_gnss_get_ecef_v_y(const mavlink_message_t* msg)
622 {
623  return _MAV_RETURN_int32_t(msg, 80);
624 }
625 
631 static inline int32_t mavlink_msg_rosflight_gnss_get_ecef_v_z(const mavlink_message_t* msg)
632 {
633  return _MAV_RETURN_int32_t(msg, 84);
634 }
635 
641 static inline uint32_t mavlink_msg_rosflight_gnss_get_s_acc(const mavlink_message_t* msg)
642 {
643  return _MAV_RETURN_uint32_t(msg, 88);
644 }
645 
651 static inline uint64_t mavlink_msg_rosflight_gnss_get_rosflight_timestamp(const mavlink_message_t* msg)
652 {
653  return _MAV_RETURN_uint64_t(msg, 16);
654 }
655 
662 static inline void mavlink_msg_rosflight_gnss_decode(const mavlink_message_t* msg, mavlink_rosflight_gnss_t* rosflight_gnss)
663 {
664 #if MAVLINK_NEED_BYTE_SWAP
665  rosflight_gnss->time = mavlink_msg_rosflight_gnss_get_time(msg);
666  rosflight_gnss->nanos = mavlink_msg_rosflight_gnss_get_nanos(msg);
669  rosflight_gnss->lat = mavlink_msg_rosflight_gnss_get_lat(msg);
670  rosflight_gnss->lon = mavlink_msg_rosflight_gnss_get_lon(msg);
671  rosflight_gnss->height = mavlink_msg_rosflight_gnss_get_height(msg);
672  rosflight_gnss->vel_n = mavlink_msg_rosflight_gnss_get_vel_n(msg);
673  rosflight_gnss->vel_e = mavlink_msg_rosflight_gnss_get_vel_e(msg);
674  rosflight_gnss->vel_d = mavlink_msg_rosflight_gnss_get_vel_d(msg);
675  rosflight_gnss->h_acc = mavlink_msg_rosflight_gnss_get_h_acc(msg);
676  rosflight_gnss->v_acc = mavlink_msg_rosflight_gnss_get_v_acc(msg);
677  rosflight_gnss->ecef_x = mavlink_msg_rosflight_gnss_get_ecef_x(msg);
678  rosflight_gnss->ecef_y = mavlink_msg_rosflight_gnss_get_ecef_y(msg);
679  rosflight_gnss->ecef_z = mavlink_msg_rosflight_gnss_get_ecef_z(msg);
680  rosflight_gnss->p_acc = mavlink_msg_rosflight_gnss_get_p_acc(msg);
681  rosflight_gnss->ecef_v_x = mavlink_msg_rosflight_gnss_get_ecef_v_x(msg);
682  rosflight_gnss->ecef_v_y = mavlink_msg_rosflight_gnss_get_ecef_v_y(msg);
683  rosflight_gnss->ecef_v_z = mavlink_msg_rosflight_gnss_get_ecef_v_z(msg);
684  rosflight_gnss->s_acc = mavlink_msg_rosflight_gnss_get_s_acc(msg);
685  rosflight_gnss->fix_type = mavlink_msg_rosflight_gnss_get_fix_type(msg);
686 #else
687  memcpy(rosflight_gnss, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN);
688 #endif
689 }
#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_uint64_t(buf, wire_offset, b)
Definition: protocol.h:149
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:148
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


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